AP_Radio: move to using updated time conv API

This commit is contained in:
Siddharth Purohit 2018-06-02 21:30:06 +05:30 committed by Andrew Tridgell
parent 9f5dbb74e7
commit ea709b9316
2 changed files with 5 additions and 5 deletions

View File

@ -303,7 +303,7 @@ void AP_Radio_cc2500::radio_init(void)
protocolState = STATE_BIND_TUNING;
}
chVTSet(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
chVTSet(&timeout_vt, chTimeMS2I(10), trigger_timeout_event, nullptr);
}
void AP_Radio_cc2500::trigger_irq_radio_event()
@ -320,7 +320,7 @@ void AP_Radio_cc2500::trigger_timeout_event(void *arg)
(void)arg;
//we are called from ISR context
chSysLockFromISR();
chVTSetI(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
chVTSetI(&timeout_vt, chTimeMS2I(10), trigger_timeout_event, nullptr);
chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
chSysUnlockFromISR();
}
@ -597,7 +597,7 @@ void AP_Radio_cc2500::irq_handler(void)
stats.recv_packets++;
packet_timer = irq_time_us;
chVTSet(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
chVTSet(&timeout_vt, chTimeMS2I(10), trigger_timeout_event, nullptr);
cc2500.Strobe(CC2500_SIDLE);
cc2500.SetPower(get_transmit_power());
@ -675,7 +675,7 @@ void AP_Radio_cc2500::irq_timeout(void)
nextChannel(chanskip);
// to keep the timeouts 1ms behind the expected time we
// need to set the timeout to 9ms
chVTSet(&timeout_vt, MS2ST(9), trigger_timeout_event, nullptr);
chVTSet(&timeout_vt, chTimeMS2I(9), trigger_timeout_event, nullptr);
lost++;
}
break;

View File

@ -950,7 +950,7 @@ void AP_Radio_cypress::setup_timeout(uint32_t timeout_ms)
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
hrt_call_after(&wait_call, timeout_ms*1000, (hrt_callout)irq_timeout_trampoline, nullptr);
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
chVTSet(&timeout_vt, MS2ST(timeout_ms), trigger_timeout_event, nullptr);
chVTSet(&timeout_vt, chTimeMS2I(timeout_ms), trigger_timeout_event, nullptr);
#endif
}