Browse Source

AP_HAL_Linux: RCInput: replace volatile with atomic

master
Lucas De Marchi 8 years ago committed by Andrew Tridgell
parent
commit
b910f230fb
  1. 2
      libraries/AP_HAL_Linux/RCInput.cpp
  2. 8
      libraries/AP_HAL_Linux/RCInput.h

2
libraries/AP_HAL_Linux/RCInput.cpp

@ -38,7 +38,7 @@ bool RCInput::new_input() @@ -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;
}

8
libraries/AP_HAL_Linux/RCInput.h

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#pragma once
#include <atomic>
#include "AP_HAL_Linux.h"
#define LINUX_RC_INPUT_NUM_CHANNELS 16
@ -42,13 +44,13 @@ public: @@ -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<unsigned int> rc_input_count;
std::atomic<unsigned int> last_rc_input_count;
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS];
uint8_t _num_channels;

Loading…
Cancel
Save