From b910f230fb52c1ed9beb8e8347e2b96e2866651c Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 9 Jan 2017 22:08:42 -0800 Subject: [PATCH] AP_HAL_Linux: RCInput: replace volatile with atomic --- libraries/AP_HAL_Linux/RCInput.cpp | 2 +- libraries/AP_HAL_Linux/RCInput.h | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_Linux/RCInput.cpp b/libraries/AP_HAL_Linux/RCInput.cpp index e1e93efcc6..a3b88664d4 100644 --- a/libraries/AP_HAL_Linux/RCInput.cpp +++ b/libraries/AP_HAL_Linux/RCInput.cpp @@ -38,7 +38,7 @@ bool RCInput::new_input() { bool ret = rc_input_count != last_rc_input_count; if (ret) { - last_rc_input_count = rc_input_count; + last_rc_input_count.store(rc_input_count); } return ret; } diff --git a/libraries/AP_HAL_Linux/RCInput.h b/libraries/AP_HAL_Linux/RCInput.h index 19b49cfe96..6ff251d845 100644 --- a/libraries/AP_HAL_Linux/RCInput.h +++ b/libraries/AP_HAL_Linux/RCInput.h @@ -1,5 +1,7 @@ #pragma once +#include + #include "AP_HAL_Linux.h" #define LINUX_RC_INPUT_NUM_CHANNELS 16 @@ -42,13 +44,13 @@ public: // add some srxl input bytes, for RCInput over a serial port bool add_srxl_input(const uint8_t *bytes, size_t nbytes); - + protected: void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1); void _update_periods(uint16_t *periods, uint8_t len); - volatile uint32_t rc_input_count; - uint32_t last_rc_input_count; + std::atomic rc_input_count; + std::atomic last_rc_input_count; uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS]; uint8_t _num_channels;