mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_PX4: added millis64() and micros64()
This commit is contained in:
parent
ead82ee581
commit
1241da466b
@ -76,14 +76,24 @@ void PX4Scheduler::init(void *unused)
|
||||
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
|
||||
}
|
||||
|
||||
uint64_t PX4Scheduler::micros64()
|
||||
{
|
||||
return hrt_absolute_time() - _sketch_start_time;
|
||||
}
|
||||
|
||||
uint64_t PX4Scheduler::millis64()
|
||||
{
|
||||
return micros64() / 1000;
|
||||
}
|
||||
|
||||
uint32_t PX4Scheduler::micros()
|
||||
{
|
||||
return (uint32_t)(hrt_absolute_time() - _sketch_start_time);
|
||||
return micros64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
uint32_t PX4Scheduler::millis()
|
||||
{
|
||||
return hrt_absolute_time() / 1000;
|
||||
return millis64() & 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -106,9 +116,9 @@ void PX4Scheduler::delay_microseconds(uint16_t usec)
|
||||
perf_end(_perf_delay);
|
||||
return;
|
||||
}
|
||||
uint32_t start = micros();
|
||||
uint32_t dt;
|
||||
while ((dt=(micros() - start)) < usec) {
|
||||
uint64_t start = micros();
|
||||
uint64_t dt;
|
||||
while ((dt=(micros64() - start)) < usec) {
|
||||
up_udelay(usec - dt);
|
||||
}
|
||||
perf_end(_perf_delay);
|
||||
|
@ -29,6 +29,8 @@ public:
|
||||
void delay(uint16_t ms);
|
||||
uint32_t millis();
|
||||
uint32_t micros();
|
||||
uint64_t millis64();
|
||||
uint64_t micros64();
|
||||
void delay_microseconds(uint16_t us);
|
||||
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
||||
void register_timer_process(AP_HAL::MemberProc);
|
||||
|
Loading…
Reference in New Issue
Block a user