AP_ADC: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:06:12 +09:00 committed by Randy Mackay
parent b331ffdd91
commit b293fb150c
2 changed files with 9 additions and 9 deletions

View File

@ -188,7 +188,7 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
default:
pga = 0.0f;
hal.console->printf("Wrong gain");
hal.scheduler->panic("ADS1115: wrong gain selected");
AP_HAL::panic("ADS1115: wrong gain selected");
break;
}
@ -198,7 +198,7 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
void AP_ADC_ADS1115::_update()
{
/* TODO: make update rate configurable */
if (hal.scheduler->micros() - _last_update_timestamp < 100000) {
if (AP_HAL::micros() - _last_update_timestamp < 100000) {
return;
}
@ -241,5 +241,5 @@ void AP_ADC_ADS1115::_update()
_i2c_sem->give();
_last_update_timestamp = hal.scheduler->micros();
_last_update_timestamp = AP_HAL::micros();
}

View File

@ -90,7 +90,7 @@ void AP_ADC_ADS7844::read(void)
if (!got) {
semfail_ctr++;
if (semfail_ctr > 100) {
hal.scheduler->panic("PANIC: failed to take _spi_sem "
AP_HAL::panic("PANIC: failed to take _spi_sem "
"100 times in AP_ADC_ADS7844::read");
}
return;
@ -124,7 +124,7 @@ void AP_ADC_ADS7844::read(void)
_spi_sem->give();
// record time of this sample
_ch6_last_sample_time_micros = hal.scheduler->micros();
_ch6_last_sample_time_micros = AP_HAL::micros();
}
@ -137,19 +137,19 @@ void AP_ADC_ADS7844::Init()
hal.scheduler->suspend_timer_procs();
_spi = hal.spi->device(AP_HAL::SPIDevice_ADS7844);
if (_spi == NULL) {
hal.scheduler->panic("PANIC: AP_ADC_ADS7844 missing SPI device "
AP_HAL::panic("PANIC: AP_ADC_ADS7844 missing SPI device "
"driver\n");
}
_spi_sem = _spi->get_semaphore();
if (_spi_sem == NULL) {
hal.scheduler->panic("PANIC: AP_ADC_ADS7844 missing SPI device "
AP_HAL::panic("PANIC: AP_ADC_ADS7844 missing SPI device "
"semaphore");
}
if (!_spi_sem->take(0)) {
hal.scheduler->panic("PANIC: failed to take _spi_sem in"
AP_HAL::panic("PANIC: failed to take _spi_sem in"
"AP_ADC_ADS7844::Init");
}
@ -168,7 +168,7 @@ void AP_ADC_ADS7844::Init()
_spi_sem->give();
_ch6_last_sample_time_micros = hal.scheduler->micros();
_ch6_last_sample_time_micros = AP_HAL::micros();
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_ADC_ADS7844::read, void));
hal.scheduler->resume_timer_procs();