Browse Source

APM_RC - Interupt safe get_last_update();

mission-4.1.18
John Arne Birkeland 12 years ago
parent
commit
4258490cd8
  1. 12
      libraries/APM_RC/APM_RC.h

12
libraries/APM_RC/APM_RC.h

@ -49,14 +49,20 @@ public: @@ -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
};

Loading…
Cancel
Save