Browse Source

AP_HAL: changed delay() to take a uint16_t

this allows for up to 32 second delays, and saves a bit of flash space
master
Andrew Tridgell 12 years ago
parent
commit
60d3df50ae
  1. 2
      libraries/AP_HAL/Scheduler.h
  2. 2
      libraries/AP_HAL_AVR/Scheduler.cpp
  3. 2
      libraries/AP_HAL_AVR/Scheduler.h
  4. 2
      libraries/AP_HAL_AVR_SITL/Scheduler.cpp
  5. 2
      libraries/AP_HAL_AVR_SITL/Scheduler.h
  6. 2
      libraries/AP_HAL_Empty/Scheduler.cpp
  7. 2
      libraries/AP_HAL_Empty/Scheduler.h

2
libraries/AP_HAL/Scheduler.h

@ -11,7 +11,7 @@ class AP_HAL::Scheduler {
public: public:
Scheduler() {} Scheduler() {}
virtual void init(void* implspecific) = 0; 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 millis() = 0;
virtual uint32_t micros() = 0; virtual uint32_t micros() = 0;
virtual void delay_microseconds(uint16_t us) = 0; virtual void delay_microseconds(uint16_t us) = 0;

2
libraries/AP_HAL_AVR/Scheduler.cpp

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

2
libraries/AP_HAL_AVR/Scheduler.h

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

2
libraries/AP_HAL_AVR_SITL/Scheduler.cpp

@ -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(); uint32_t start = micros();

2
libraries/AP_HAL_AVR_SITL/Scheduler.h

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

2
libraries/AP_HAL_Empty/Scheduler.cpp

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

2
libraries/AP_HAL_Empty/Scheduler.h

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

Loading…
Cancel
Save