APM_RC - Interupt safe get_last_update();

This commit is contained in:
John Arne Birkeland 2012-11-15 22:42:28 +01:00
parent 3a4d122e32
commit 47d2602019
1 changed files with 9 additions and 3 deletions

View File

@ -49,14 +49,20 @@ public:
virtual void Force_Out2_Out3(void) = 0;
virtual void Force_Out6_Out7(void) = 0;
// get the time of the last radio update
virtual uint32_t get_last_update() { return _last_update; };
// get the time of the last radio update (_last_update modified by interrupt, so reading of variable must be interrupt safe)
virtual uint32_t get_last_update() {
uint32_t _tmp = _last_update;
while( _tmp != _last_update ) _tmp = _last_update;
return _tmp;
};
protected:
uint16_t _map_speed(uint16_t speed_hz) {
return 2000000UL / speed_hz;
}
static uint32_t _last_update;
static volatile uint32_t _last_update; // Modified by interrupt
};