mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: RCInput: replace volatile with atomic
This commit is contained in:
parent
bdbb07a3b1
commit
b910f230fb
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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:
|
|||
|
||||
// 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…
Reference in New Issue