AP_Scheduler: use millis/micros/panic functions
This commit is contained in:
parent
82a14b183d
commit
81186e5416
@ -61,7 +61,7 @@ void AP_Scheduler::tick(void)
|
||||
*/
|
||||
void AP_Scheduler::run(uint16_t time_available)
|
||||
{
|
||||
uint32_t run_started_usec = hal.scheduler->micros();
|
||||
uint32_t run_started_usec = AP_HAL::micros();
|
||||
uint32_t now = run_started_usec;
|
||||
|
||||
for (uint8_t i=0; i<_num_tasks; i++) {
|
||||
@ -97,7 +97,7 @@ void AP_Scheduler::run(uint16_t time_available)
|
||||
_last_run[i] = _tick_counter;
|
||||
|
||||
// work out how long the event actually took
|
||||
now = hal.scheduler->micros();
|
||||
now = AP_HAL::micros();
|
||||
uint32_t time_taken = now - _task_time_started;
|
||||
|
||||
if (time_taken > _task_time_allowed) {
|
||||
@ -134,7 +134,7 @@ update_spare_ticks:
|
||||
*/
|
||||
uint16_t AP_Scheduler::time_available_usec(void)
|
||||
{
|
||||
uint32_t dt = hal.scheduler->micros() - _task_time_started;
|
||||
uint32_t dt = AP_HAL::micros() - _task_time_started;
|
||||
if (dt > _task_time_allowed) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -84,7 +84,7 @@ void SchedTest::ins_update(void)
|
||||
*/
|
||||
void SchedTest::one_hz_print(void)
|
||||
{
|
||||
hal.console->printf("one_hz: t=%lu\n", (unsigned long)hal.scheduler->millis());
|
||||
hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
|
||||
}
|
||||
|
||||
/*
|
||||
@ -92,7 +92,7 @@ void SchedTest::one_hz_print(void)
|
||||
*/
|
||||
void SchedTest::five_second_call(void)
|
||||
{
|
||||
hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)hal.scheduler->millis(), ins_counter);
|
||||
hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), ins_counter);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user