AP_HAL: support micros64() and millis64() on all platforms

this will allow for 64 bit timestamps in DF logs (Peter is working on
that)
This commit is contained in:
Andrew Tridgell 2015-04-30 12:17:34 +10:00
parent c65f5a1bda
commit df21c6c68d
5 changed files with 34 additions and 3 deletions

View File

@ -15,11 +15,8 @@ public:
virtual void delay(uint16_t ms) = 0;
virtual uint32_t millis() = 0;
virtual uint32_t micros() = 0;
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
// offer non-wrapping 64 bit versions on faster CPUs
virtual uint64_t millis64() = 0;
virtual uint64_t micros64() = 0;
#endif
/*
delay for the given number of microseconds. This needs to be as

View File

@ -66,6 +66,24 @@ uint32_t AVRScheduler::millis() {
return _timer.millis();
}
/*
64 bit version of millis(). This wraps at 32 bits on AVR
*/
uint64_t AVRScheduler::millis64() {
return millis();
}
/*
64 bit version of micros(). This wraps when 32 bit millis() wraps
*/
uint64_t AVRScheduler::micros64() {
// this is slow, but solves the problem with logging uint64_t timestamps
uint64_t ret = millis();
ret *= 1000ULL;
ret += micros() % 1000UL;
return ret;
}
void AVRScheduler::delay_microseconds(uint16_t us) {
_timer.delay_microseconds(us);
}

View File

@ -28,6 +28,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);

View File

@ -103,6 +103,18 @@ uint32_t FLYMAPLEScheduler::micros() {
return libmaple_micros();
}
uint64_t FLYMAPLEScheduler::millis64() {
return millis();
}
uint64_t FLYMAPLEScheduler::micros64() {
// this is slow, but solves the problem with logging uint64_t timestamps
uint64_t ret = millis();
ret *= 1000ULL;
ret += micros() % 1000;
return ret;
}
void FLYMAPLEScheduler::delay_microseconds(uint16_t us)
{
delay_us(us);

View File

@ -30,6 +30,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);