AP_HAL_FLYMAPLE: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:10:39 +09:00 committed by Randy Mackay
parent c33b86a783
commit f03eec59d6
6 changed files with 15 additions and 15 deletions

View File

@ -134,7 +134,7 @@ void FLYMAPLEAnalogSource::setup_read() {
hal.gpio->write(digital_pin, 1);
}
if (_settle_time_ms != 0) {
_read_start_time_ms = hal.scheduler->millis();
_read_start_time_ms = AP_HAL::millis();
}
adc_reg_map *regs = ADC1->regs;
adc_set_reg_seqlen(ADC1, 1);
@ -158,7 +158,7 @@ void FLYMAPLEAnalogSource::stop_read() {
bool FLYMAPLEAnalogSource::reading_settled()
{
if (_settle_time_ms != 0 && (hal.scheduler->millis() - _read_start_time_ms) < _settle_time_ms) {
if (_settle_time_ms != 0 && (AP_HAL::millis() - _read_start_time_ms) < _settle_time_ms) {
return false;
}
return true;

View File

@ -51,7 +51,7 @@ FLYMAPLERCInput::FLYMAPLERCInput()
// This interrupt triggers on a negative transiution of the PPM-SIM pin
void FLYMAPLERCInput::_timer_capt_cb(void)
{
_last_input_interrupt_time = hal.scheduler->millis();
_last_input_interrupt_time = AP_HAL::millis();
static uint16 previous_count;
static uint8 channel_ctr;
@ -128,7 +128,7 @@ void FLYMAPLERCInput::init(void* machtnichts)
}
bool FLYMAPLERCInput::new_input() {
if ((hal.scheduler->millis() - _last_input_interrupt_time) > 50)
if ((AP_HAL::millis() - _last_input_interrupt_time) > 50)
_valid_channels = 0; // Lost RC Input?
return _valid_channels != 0;
}

View File

@ -44,7 +44,7 @@ bool FLYMAPLESemaphore::give() {
bool FLYMAPLESemaphore::take(uint32_t timeout_ms) {
if (hal.scheduler->in_timerprocess()) {
hal.scheduler->panic("PANIC: FLYMAPLESemaphore::take used from "
AP_HAL::panic("PANIC: FLYMAPLESemaphore::take used from "
"inside timer process");
return false; /* Never reached - panic does not return */
}

View File

@ -41,7 +41,7 @@ void setup()
}
hal.console->println("initialisation complete.");
hal.scheduler->delay(1000);
timer = hal.scheduler->micros();
timer = AP_HAL::micros();
}
void loop()
@ -50,17 +50,17 @@ void loop()
static uint32_t last_print;
// accumulate values at 100Hz
if ((hal.scheduler->micros()- timer) > 20000L) {
if ((AP_HAL::micros()- timer) > 20000L) {
bmp085.accumulate();
timer = hal.scheduler->micros();
timer = AP_HAL::micros();
}
// print at 10Hz
if ((hal.scheduler->millis()- last_print) >= 100) {
uint32_t start = hal.scheduler->micros();
last_print = hal.scheduler->millis();
if ((AP_HAL::millis()- last_print) >= 100) {
uint32_t start = AP_HAL::micros();
last_print = AP_HAL::millis();
bmp085.read();
uint32_t read_time = hal.scheduler->micros() - start;
uint32_t read_time = AP_HAL::micros() - start;
if (! bmp085.healthy) {
hal.console->println("not healthy");
return;

View File

@ -19,7 +19,7 @@ void setup (void) {
spidev = hal.spi->device(AP_HAL::SPIDevice_MPU6000); // Not really MPU6000, just a generic SPU driver
if (!spidev)
hal.scheduler->panic("Starting AP_HAL_FLYMAPLE::SPIDriver failed to get spidev\r\n");
AP_HAL::panic("Starting AP_HAL_FLYMAPLE::SPIDriver failed to get spidev\r\n");
}
void loop (void) {

View File

@ -73,12 +73,12 @@ void setup (void) {
AP_HAL::SPIDeviceDriver *dataflash = hal.spi->device(AP_HAL::SPIDevice_Dataflash); // not really
if (dataflash == NULL) {
hal.scheduler->panic("Error: No SPIDeviceDriver!");
AP_HAL::panic("Error: No SPIDeviceDriver!");
}
sem = dataflash->get_semaphore();
if (sem == NULL) {
hal.scheduler->panic("Error: No SPIDeviceDriver semaphore!");
AP_HAL::panic("Error: No SPIDeviceDriver semaphore!");
}
hal.scheduler->register_timer_process(async_blinker);