AP_HAL: changed delay() to take a uint16_t

this allows for up to 32 second delays, and saves a bit of flash space
This commit is contained in:
Andrew Tridgell 2012-12-20 13:16:10 +11:00
parent 772f93ea10
commit 60d3df50ae
7 changed files with 7 additions and 7 deletions

View File

@ -11,7 +11,7 @@ class AP_HAL::Scheduler {
public:
Scheduler() {}
virtual void init(void* implspecific) = 0;
virtual void delay(uint32_t ms) = 0;
virtual void delay(uint16_t ms) = 0;
virtual uint32_t millis() = 0;
virtual uint32_t micros() = 0;
virtual void delay_microseconds(uint16_t us) = 0;

View File

@ -64,7 +64,7 @@ void AVRScheduler::delay_microseconds(uint16_t us) {
_timer.delay_microseconds(us);
}
void AVRScheduler::delay(uint32_t ms)
void AVRScheduler::delay(uint16_t ms)
{
uint32_t start = _timer.micros();

View File

@ -25,7 +25,7 @@ public:
/* init: implementation-specific void* argument expected to be an
* AP_HAL_AVR::ISRRegistry*. */
void init(void *isrregistry);
void delay(uint32_t ms);
void delay(uint16_t ms);
uint32_t millis();
uint32_t micros();
void delay_microseconds(uint16_t us);

View File

@ -60,7 +60,7 @@ void SITLScheduler::delay_microseconds(uint16_t usec)
}
}
void SITLScheduler::delay(uint32_t ms)
void SITLScheduler::delay(uint16_t ms)
{
uint32_t start = micros();

View File

@ -16,7 +16,7 @@ public:
/* AP_HAL::Scheduler methods */
void init(void *unused);
void delay(uint32_t ms);
void delay(uint16_t ms);
uint32_t millis();
uint32_t micros();
void delay_microseconds(uint16_t us);

View File

@ -11,7 +11,7 @@ EmptyScheduler::EmptyScheduler()
void EmptyScheduler::init(void* machtnichts)
{}
void EmptyScheduler::delay(uint32_t ms)
void EmptyScheduler::delay(uint16_t ms)
{}
uint32_t EmptyScheduler::millis() {

View File

@ -8,7 +8,7 @@ class Empty::EmptyScheduler : public AP_HAL::Scheduler {
public:
EmptyScheduler();
void init(void* machtnichts);
void delay(uint32_t ms);
void delay(uint16_t ms);
uint32_t millis();
uint32_t micros();
void delay_microseconds(uint16_t us);