mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: updates for new ChibiOS version
This commit is contained in:
parent
7aba99e229
commit
9727328e0c
|
@ -130,7 +130,7 @@ volatile unsigned timer[NTIMERS];
|
|||
*/
|
||||
static void sys_tick_handler(void *ctx)
|
||||
{
|
||||
chVTSetI(&systick_vt, MS2ST(1), sys_tick_handler, nullptr);
|
||||
chVTSetI(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);
|
||||
uint8_t i;
|
||||
for (i = 0; i < NTIMERS; i++)
|
||||
if (timer[i] > 0) {
|
||||
|
@ -145,7 +145,7 @@ static void sys_tick_handler(void *ctx)
|
|||
|
||||
static void delay(unsigned msec)
|
||||
{
|
||||
chThdSleep(MS2ST(msec));
|
||||
chThdSleep(chTimeMS2I(msec));
|
||||
}
|
||||
|
||||
static void
|
||||
|
@ -222,8 +222,8 @@ jump_to_app()
|
|||
led_set(LED_OFF);
|
||||
|
||||
// resetting the clocks is needed for loading NuttX
|
||||
rccDisableAPB1(~0, 0);
|
||||
rccDisableAPB2(~0, 0);
|
||||
rccDisableAPB1(~0);
|
||||
rccDisableAPB2(~0);
|
||||
#if HAL_USE_SERIAL_USB == TRUE
|
||||
rccResetOTG_FS();
|
||||
rccResetOTG_HS();
|
||||
|
@ -332,7 +332,7 @@ bootloader(unsigned timeout)
|
|||
bool done_get_device = false;
|
||||
|
||||
chVTObjectInit(&systick_vt);
|
||||
chVTSet(&systick_vt, MS2ST(1), sys_tick_handler, nullptr);
|
||||
chVTSet(&systick_vt, chTimeMS2I(1), sys_tick_handler, nullptr);
|
||||
|
||||
/* if we are working with a timeout, start it running */
|
||||
if (timeout) {
|
||||
|
|
|
@ -29,7 +29,7 @@ int16_t cin(unsigned timeout_ms)
|
|||
uint8_t b = 0;
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
|
||||
if (locked_uart == -1 || locked_uart == i) {
|
||||
if (chnReadTimeout(uarts[i], &b, 1, MS2ST(timeout_ms)) == 1) {
|
||||
if (chnReadTimeout(uarts[i], &b, 1, chTimeMS2I(timeout_ms)) == 1) {
|
||||
last_uart = i;
|
||||
return b;
|
||||
}
|
||||
|
@ -43,7 +43,7 @@ int cin_word(uint32_t *wp, unsigned timeout_ms)
|
|||
{
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
|
||||
if (locked_uart == -1 || locked_uart == i) {
|
||||
if (chnReadTimeout(uarts[i], (uint8_t *)wp, 4, MS2ST(timeout_ms)) == 4) {
|
||||
if (chnReadTimeout(uarts[i], (uint8_t *)wp, 4, chTimeMS2I(timeout_ms)) == 4) {
|
||||
last_uart = i;
|
||||
return 0;
|
||||
}
|
||||
|
@ -56,7 +56,7 @@ int cin_word(uint32_t *wp, unsigned timeout_ms)
|
|||
|
||||
void cout(uint8_t *data, uint32_t len)
|
||||
{
|
||||
chnWriteTimeout(uarts[last_uart], data, len, MS2ST(100));
|
||||
chnWriteTimeout(uarts[last_uart], data, len, chTimeMS2I(100));
|
||||
}
|
||||
|
||||
static uint32_t flash_base_page;
|
||||
|
@ -248,7 +248,7 @@ void uprintf(const char *fmt, ...)
|
|||
va_start(ap, fmt);
|
||||
uint32_t n = vsnprintf(msg, sizeof(msg), fmt, ap);
|
||||
va_end(ap);
|
||||
chnWriteTimeout(&SDU1, (const uint8_t *)msg, n, MS2ST(100));
|
||||
chnWriteTimeout(&SDU1, (const uint8_t *)msg, n, chTimeMS2I(100));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue