HAL_ChibiOS: move tto using updated time conversion API

This commit is contained in:
Siddharth Purohit 2018-06-02 21:26:42 +05:30 committed by Andrew Tridgell
parent 4e8d072d6d
commit 395c48933c
5 changed files with 8 additions and 13 deletions

View File

@ -243,10 +243,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
if(send_len == 0) {
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv, recv_len, MS2ST(timeout_ms));
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv, recv_len, chTimeMS2I(timeout_ms));
} else {
ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send, send_len,
recv, recv_len, MS2ST(timeout_ms));
recv, recv_len, chTimeMS2I(timeout_ms));
}
i2cStop(I2CD[bus.busnum].i2c);

View File

@ -1075,7 +1075,7 @@ bool RCOutput::serial_write_byte(uint8_t b)
send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t));
// wait for the event
eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, MS2ST(2));
eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(2));
serial_group->in_serial_dma = false;
@ -1167,7 +1167,7 @@ void RCOutput::serial_bit_irq(void)
*/
bool RCOutput::serial_read_byte(uint8_t &b)
{
bool timed_out = ((chEvtWaitAnyTimeout(serial_event_mask, MS2ST(10)) & serial_event_mask) == 0);
bool timed_out = ((chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(10)) & serial_event_mask) == 0);
uint16_t byteval = irq.byteval;

View File

@ -99,12 +99,7 @@ void Scheduler::delay_microseconds(uint16_t usec)
return;
}
uint32_t ticks;
if (usec >= 4096) {
// we need to use 64 bit calculations for tick conversions
ticks = US2ST64(usec);
} else {
ticks = US2ST(usec);
}
ticks = chTimeUS2I(usec);
if (ticks == 0) {
// calling with ticks == 0 causes a hard fault on ChibiOS
ticks = 1;

View File

@ -71,7 +71,7 @@ void UARTDriver::uart_thread(void* arg)
uart_thread_ctx = chThdGetSelfX();
while (true) {
eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(1));
eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(1));
uint32_t now = AP_HAL::micros();
if (now - last_thread_run_us >= 1000) {
// run them all if it's been more than 1ms since we ran
@ -600,7 +600,7 @@ bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
}
_wait.n = n;
_wait.thread_ctx = chThdGetSelfX();
eventmask_t mask = chEvtWaitAnyTimeout(EVT_DATA, MS2ST(timeout_ms));
eventmask_t mask = chEvtWaitAnyTimeout(EVT_DATA, chTimeMS2I(timeout_ms));
return (mask & EVT_DATA) != 0;
}

View File

@ -37,7 +37,7 @@ uint64_t hrt_micros()
// since we are definitely going to get called atleast once in
// a full timer period
if (last_micros > micros) {
const uint64_t step = ST2US(1ULL<<CH_CFG_ST_RESOLUTION);
const uint64_t step = TIME_MAX_SYSTIME;
timer_base += step;
micros += step;
}