AP_FrSkyTelem: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:10:09 +09:00 committed by Randy Mackay
parent 032acaaee4
commit 2b982d6391
1 changed files with 1 additions and 1 deletions

View File

@ -156,7 +156,7 @@ void AP_Frsky_Telem::init_uart_for_sport()
*/
void AP_Frsky_Telem::send_hub_frame()
{
uint32_t now = hal.scheduler->millis();
uint32_t now = AP_HAL::millis();
// send frame1 every 200ms
if (now - _last_frame1_ms > 200) {