mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Radio: move to using updated time conv API
This commit is contained in:
parent
9f5dbb74e7
commit
ea709b9316
@ -303,7 +303,7 @@ void AP_Radio_cc2500::radio_init(void)
|
|||||||
protocolState = STATE_BIND_TUNING;
|
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()
|
void AP_Radio_cc2500::trigger_irq_radio_event()
|
||||||
@ -320,7 +320,7 @@ void AP_Radio_cc2500::trigger_timeout_event(void *arg)
|
|||||||
(void)arg;
|
(void)arg;
|
||||||
//we are called from ISR context
|
//we are called from ISR context
|
||||||
chSysLockFromISR();
|
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);
|
chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
|
||||||
chSysUnlockFromISR();
|
chSysUnlockFromISR();
|
||||||
}
|
}
|
||||||
@ -597,7 +597,7 @@ void AP_Radio_cc2500::irq_handler(void)
|
|||||||
stats.recv_packets++;
|
stats.recv_packets++;
|
||||||
|
|
||||||
packet_timer = irq_time_us;
|
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.Strobe(CC2500_SIDLE);
|
||||||
cc2500.SetPower(get_transmit_power());
|
cc2500.SetPower(get_transmit_power());
|
||||||
@ -675,7 +675,7 @@ void AP_Radio_cc2500::irq_timeout(void)
|
|||||||
nextChannel(chanskip);
|
nextChannel(chanskip);
|
||||||
// to keep the timeouts 1ms behind the expected time we
|
// to keep the timeouts 1ms behind the expected time we
|
||||||
// need to set the timeout to 9ms
|
// 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++;
|
lost++;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -950,7 +950,7 @@ void AP_Radio_cypress::setup_timeout(uint32_t timeout_ms)
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
hrt_call_after(&wait_call, timeout_ms*1000, (hrt_callout)irq_timeout_trampoline, nullptr);
|
hrt_call_after(&wait_call, timeout_ms*1000, (hrt_callout)irq_timeout_trampoline, nullptr);
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#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
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user