AP_HAL_VRBRAIN: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:11:33 +09:00 committed by Randy Mackay
parent 85d12efbef
commit 2314578f6f
6 changed files with 28 additions and 28 deletions

View File

@ -194,7 +194,7 @@ void VRBRAINAnalogIn::init(void* machtnichts)
{
_adc_fd = open(ADC_DEVICE_PATH, O_RDONLY | O_NONBLOCK);
if (_adc_fd == -1) {
hal.scheduler->panic("Unable to open " ADC_DEVICE_PATH);
AP_HAL::panic("Unable to open " ADC_DEVICE_PATH);
}
_battery_handle = orb_subscribe(ORB_ID(battery_status));
_servorail_handle = orb_subscribe(ORB_ID(servorail_status));
@ -215,7 +215,7 @@ void VRBRAINAnalogIn::next_stop_pin(void)
VRBRAIN::VRBRAINAnalogSource *c = _channels[idx];
if (c && c->_stop_pin != -1) {
// found another stop pin
_stop_pin_change_time = hal.scheduler->millis();
_stop_pin_change_time = AP_HAL::millis();
_current_stop_pin_i = idx;
// set that pin high
@ -241,7 +241,7 @@ void VRBRAINAnalogIn::next_stop_pin(void)
void VRBRAINAnalogIn::_timer_tick(void)
{
// read adc at 100Hz
uint32_t now = hal.scheduler->micros();
uint32_t now = AP_HAL::micros();
uint32_t delta_t = now - _last_run;
if (delta_t < 10000) {
return;
@ -271,7 +271,7 @@ void VRBRAINAnalogIn::_timer_tick(void)
// the stop pin has been settling for enough time
if (c->_stop_pin == -1 ||
(_current_stop_pin_i == j &&
hal.scheduler->millis() - _stop_pin_change_time > c->_settle_time_ms)) {
AP_HAL::millis() - _stop_pin_change_time > c->_settle_time_ms)) {
c->_add_value(buf_adc[i].am_data, _board_voltage);
if (c->_stop_pin != -1 && _current_stop_pin_i == j) {
next_stop_pin();

View File

@ -33,7 +33,7 @@ void VRBRAINGPIO::init()
{
_led_fd = open(LED_DEVICE_PATH, O_RDWR);
if (_led_fd == -1) {
hal.scheduler->panic("Unable to open " LED_DEVICE_PATH);
AP_HAL::panic("Unable to open " LED_DEVICE_PATH);
}
if (ioctl(_led_fd, LED_OFF, LED_BLUE) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO LED BLUE\n");
@ -63,7 +63,7 @@ void VRBRAINGPIO::init()
#if defined(BUZZER_EXT)
_buzzer_fd = open(BUZZER_DEVICE_PATH, O_RDWR);
if (_buzzer_fd == -1) {
hal.scheduler->panic("Unable to open " BUZZER_DEVICE_PATH);
AP_HAL::panic("Unable to open " BUZZER_DEVICE_PATH);
}
if (ioctl(_buzzer_fd, BUZZER_OFF, BUZZER_EXT) != 0) {
hal.console->printf("GPIO: Unable to setup GPIO BUZZER\n");

View File

@ -14,7 +14,7 @@ void VRBRAINRCInput::init(void* unused)
_perf_rcin = perf_alloc(PC_ELAPSED, "APM_rcin");
_rc_sub = orb_subscribe(ORB_ID(input_rc));
if (_rc_sub == -1) {
hal.scheduler->panic("Unable to subscribe to input_rc");
AP_HAL::panic("Unable to subscribe to input_rc");
}
clear_overrides();
pthread_mutex_init(&rcin_mutex, NULL);

View File

@ -21,7 +21,7 @@ void VRBRAINRCOutput::init(void* unused)
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
_pwm_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);
if (_pwm_fd == -1) {
hal.scheduler->panic("Unable to open " PWM_OUTPUT_DEVICE_PATH);
AP_HAL::panic("Unable to open " PWM_OUTPUT_DEVICE_PATH);
}
if (ioctl(_pwm_fd, PWM_SERVO_ARM, 0) != 0) {
hal.console->printf("RCOutput: Unable to setup IO arming\n");
@ -199,7 +199,7 @@ void VRBRAINRCOutput::read(uint16_t* period_us, uint8_t len)
void VRBRAINRCOutput::_timer_tick(void)
{
uint32_t now = hal.scheduler->micros();
uint32_t now = AP_HAL::micros();
// always send at least at 20Hz, otherwise the IO board may think
// we are dead

View File

@ -45,14 +45,14 @@ uint32_t VRBRAINStorage::_mtd_signature(void)
{
int mtd_fd = open(MTD_PARAMS_FILE, O_RDONLY);
if (mtd_fd == -1) {
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to open " MTD_PARAMS_FILE);
}
uint32_t v;
if (lseek(mtd_fd, MTD_SIGNATURE_OFFSET, SEEK_SET) != MTD_SIGNATURE_OFFSET) {
hal.scheduler->panic("Failed to seek in " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to seek in " MTD_PARAMS_FILE);
}
if (read(mtd_fd, &v, sizeof(v)) != sizeof(v)) {
hal.scheduler->panic("Failed to read signature from " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to read signature from " MTD_PARAMS_FILE);
}
close(mtd_fd);
return v;
@ -65,14 +65,14 @@ void VRBRAINStorage::_mtd_write_signature(void)
{
int mtd_fd = open(MTD_PARAMS_FILE, O_WRONLY);
if (mtd_fd == -1) {
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to open " MTD_PARAMS_FILE);
}
uint32_t v = MTD_SIGNATURE;
if (lseek(mtd_fd, MTD_SIGNATURE_OFFSET, SEEK_SET) != MTD_SIGNATURE_OFFSET) {
hal.scheduler->panic("Failed to seek in " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to seek in " MTD_PARAMS_FILE);
}
if (write(mtd_fd, &v, sizeof(v)) != sizeof(v)) {
hal.scheduler->panic("Failed to write signature in " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to write signature in " MTD_PARAMS_FILE);
}
close(mtd_fd);
}
@ -92,7 +92,7 @@ void VRBRAINStorage::_upgrade_to_mtd(void)
int mtd_fd = open(MTD_PARAMS_FILE, O_WRONLY);
if (mtd_fd == -1) {
hal.scheduler->panic("Unable to open MTD for upgrade");
AP_HAL::panic("Unable to open MTD for upgrade");
}
if (::read(old_fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
@ -105,7 +105,7 @@ void VRBRAINStorage::_upgrade_to_mtd(void)
ssize_t ret;
if ((ret=::write(mtd_fd, _buffer, sizeof(_buffer))) != sizeof(_buffer)) {
::printf("mtd write of %u bytes returned %d errno=%d\n", sizeof(_buffer), ret, errno);
hal.scheduler->panic("Unable to write MTD for upgrade");
AP_HAL::panic("Unable to write MTD for upgrade");
}
close(mtd_fd);
#if STORAGE_RENAME_OLD_FILE
@ -126,7 +126,7 @@ void VRBRAINStorage::_storage_open(void)
// VRBRAIN should always have /fs/mtd_params
if (!_have_mtd) {
hal.scheduler->panic("Failed to find " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to find " MTD_PARAMS_FILE);
}
/*
@ -152,7 +152,7 @@ void VRBRAINStorage::_storage_open(void)
_dirty_mask = 0;
int fd = open(MTD_PARAMS_FILE, O_RDONLY);
if (fd == -1) {
hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to open " MTD_PARAMS_FILE);
}
const uint16_t chunk_size = 128;
for (uint16_t ofs=0; ofs<sizeof(_buffer); ofs += chunk_size) {
@ -160,7 +160,7 @@ void VRBRAINStorage::_storage_open(void)
if (ret != chunk_size) {
::printf("storage read of %u bytes at %u to %p failed - got %d errno=%d\n",
(unsigned)sizeof(_buffer), (unsigned)ofs, &_buffer[ofs], (int)ret, (int)errno);
hal.scheduler->panic("Failed to read " MTD_PARAMS_FILE);
AP_HAL::panic("Failed to read " MTD_PARAMS_FILE);
}
}
close(fd);

View File

@ -179,10 +179,10 @@ void VRBRAINUARTDriver::try_initialise(void)
if (_initialised) {
return;
}
if ((hal.scheduler->millis() - _last_initialise_attempt_ms) < 2000) {
if ((AP_HAL::millis() - _last_initialise_attempt_ms) < 2000) {
return;
}
_last_initialise_attempt_ms = hal.scheduler->millis();
_last_initialise_attempt_ms = AP_HAL::millis();
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED || !hal.util->get_soft_armed()) {
begin(0);
}
@ -387,7 +387,7 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
}
} else {
if (_os_start_auto_space - nwrite + 1 >= _total_written &&
(hal.scheduler->micros64() - _first_write_time) > 500*1000UL) {
(AP_HAL::micros64() - _first_write_time) > 500*1000UL) {
// it doesn't look like hw flow control is working
::printf("disabling flow control on %s _total_written=%u\n",
_devpath, (unsigned)_total_written);
@ -405,7 +405,7 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
if (ret > 0) {
BUF_ADVANCEHEAD(_writebuf, ret);
_last_write_time = hal.scheduler->micros64();
_last_write_time = AP_HAL::micros64();
_total_written += ret;
if (! _first_write_time && _total_written > 5) {
_first_write_time = _last_write_time;
@ -413,12 +413,12 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
return ret;
}
if (hal.scheduler->micros64() - _last_write_time > 2000 &&
if (AP_HAL::micros64() - _last_write_time > 2000 &&
_flow_control == FLOW_CONTROL_DISABLE) {
#if 0
// this trick is disabled for now, as it sometimes blocks on
// re-opening the ttyACM0 port, which would cause a crash
if (hal.scheduler->micros64() - _last_write_time > 2000000) {
if (AP_HAL::micros64() - _last_write_time > 2000000) {
// we haven't done a successful write for 2 seconds - try
// reopening the port
_initialised = false;
@ -431,11 +431,11 @@ int VRBRAINUARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
return n;
}
_last_write_time = hal.scheduler->micros64();
_last_write_time = AP_HAL::micros64();
_initialised = true;
}
#else
_last_write_time = hal.scheduler->micros64();
_last_write_time = AP_HAL::micros64();
#endif
// we haven't done a successful write for 2ms, which means the
// port is running at less than 500 bytes/sec. Start