From e194c6c740c7f67452260dc7777cf6ccbf8fb627 Mon Sep 17 00:00:00 2001 From: John Arne Birkeland Date: Wed, 21 Nov 2012 10:34:04 +0100 Subject: [PATCH] APM_RC: Modified get_last_update() to be more interrupt friendly --- libraries/APM_RC/APM_RC.cpp | 2 +- libraries/APM_RC/APM_RC.h | 21 +++++++++++++++------ libraries/APM_RC/APM_RC_APM1.cpp | 2 +- libraries/APM_RC/APM_RC_APM2.cpp | 2 +- 4 files changed, 18 insertions(+), 9 deletions(-) diff --git a/libraries/APM_RC/APM_RC.cpp b/libraries/APM_RC/APM_RC.cpp index 87c2d32b98..554ccd4934 100644 --- a/libraries/APM_RC/APM_RC.cpp +++ b/libraries/APM_RC/APM_RC.cpp @@ -5,5 +5,5 @@ */ #include "APM_RC.h" -volatile uint32_t APM_RC_Class::_last_update; +volatile uint8_t APM_RC_Class::_ppm_count; diff --git a/libraries/APM_RC/APM_RC.h b/libraries/APM_RC/APM_RC.h index 48ac4c4721..0c5fafe9a1 100644 --- a/libraries/APM_RC/APM_RC.h +++ b/libraries/APM_RC/APM_RC.h @@ -50,20 +50,29 @@ public: virtual void Force_Out2_Out3(void) = 0; virtual void Force_Out6_Out7(void) = 0; - // get the time of the last radio update (_last_update modified by interrupt, so reading of variable must be interrupt safe) + // get the approximate time of the last radio ppm update + // - resolution of the return time in ms is defined by how often get_last_update() is called + // - _ppm_count is modified by interrupt, but type is volatile uint8_t making it atomic for reading and writting outside the interrupt virtual uint32_t get_last_update() { - - uint32_t _tmp = _last_update; - while( _tmp != _last_update ) _tmp = _last_update; + static uint32_t _last_update_time = millis(); // Initialize with current time to prevent false trigger - return _tmp; + // PPM refresh? + if( _ppm_count > 0) { + // Reset _ppm_count + _ppm_count = 0; + + // Approximate time (very much so) of last update + _last_update_time = millis(); + } + + return _last_update_time; }; protected: uint16_t _map_speed(uint16_t speed_hz) { return 2000000UL / speed_hz; } - static volatile uint32_t _last_update; // Modified by interrupt + static volatile uint8_t _ppm_count; // Modified by interrupt }; diff --git a/libraries/APM_RC/APM_RC_APM1.cpp b/libraries/APM_RC/APM_RC_APM1.cpp index 7f648e50f6..35faf456a0 100644 --- a/libraries/APM_RC/APM_RC_APM1.cpp +++ b/libraries/APM_RC/APM_RC_APM1.cpp @@ -58,7 +58,7 @@ void APM_RC_APM1::_timer4_capt_cb(void) // pass through values if at least a minimum number of channels received if( PPM_Counter >= MIN_CHANNELS ) { _radio_status = 1; - _last_update = millis(); + _ppm_count++; } PPM_Counter=0; } diff --git a/libraries/APM_RC/APM_RC_APM2.cpp b/libraries/APM_RC/APM_RC_APM2.cpp index aa6847fa96..6308e82b5e 100644 --- a/libraries/APM_RC/APM_RC_APM2.cpp +++ b/libraries/APM_RC/APM_RC_APM2.cpp @@ -58,7 +58,7 @@ void APM_RC_APM2::_timer5_capt_cb(void) // pass through values if at least a minimum number of channels received if( frame_idx >= MIN_CHANNELS ) { _radio_status = 1; - _last_update = millis(); + _ppm_count++; } frame_idx=0; } else {