mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_HAL: rename RCInput's valid() fn to valid_channels
This commit is contained in:
parent
a28c6df611
commit
bbbd90c430
@ -23,7 +23,7 @@ public:
|
|||||||
* Could be less than or greater than 8 depending on your incoming radio
|
* Could be less than or greater than 8 depending on your incoming radio
|
||||||
* or PPM stream
|
* or PPM stream
|
||||||
*/
|
*/
|
||||||
virtual uint8_t valid() = 0;
|
virtual uint8_t valid_channels() = 0;
|
||||||
|
|
||||||
/* Read a single channel at a time */
|
/* Read a single channel at a time */
|
||||||
virtual uint16_t read(uint8_t ch) = 0;
|
virtual uint16_t read(uint8_t ch) = 0;
|
||||||
|
@ -17,13 +17,13 @@ public:
|
|||||||
void init(void* isrregistry);
|
void init(void* isrregistry);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* valid():
|
* valid_channels():
|
||||||
* Return the number of currently valid channels.
|
* Return the number of currently valid channels.
|
||||||
* Typically 0 (no valid radio channels) or 8 (implementation-defined)
|
* Typically 0 (no valid radio channels) or 8 (implementation-defined)
|
||||||
* Could be less than or greater than 8 depending on your incoming radio
|
* Could be less than or greater than 8 depending on your incoming radio
|
||||||
* or PPM stream
|
* or PPM stream
|
||||||
*/
|
*/
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* read(uint8_t):
|
* read(uint8_t):
|
||||||
@ -58,7 +58,7 @@ private:
|
|||||||
static void _timer4_capt_cb(void);
|
static void _timer4_capt_cb(void);
|
||||||
/* private variables to communicate with input capture isr */
|
/* private variables to communicate with input capture isr */
|
||||||
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
||||||
static volatile uint8_t _valid;
|
static volatile uint8_t _valid_channels;
|
||||||
|
|
||||||
/* override state */
|
/* override state */
|
||||||
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
||||||
@ -67,7 +67,7 @@ private:
|
|||||||
class AP_HAL_AVR::APM2RCInput : public AP_HAL::RCInput {
|
class AP_HAL_AVR::APM2RCInput : public AP_HAL::RCInput {
|
||||||
/* Pass in a AP_HAL_AVR::ISRRegistry* as void*. */
|
/* Pass in a AP_HAL_AVR::ISRRegistry* as void*. */
|
||||||
void init(void* isrregistry);
|
void init(void* isrregistry);
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
bool set_overrides(int16_t *overrides, uint8_t len);
|
bool set_overrides(int16_t *overrides, uint8_t len);
|
||||||
@ -78,7 +78,7 @@ private:
|
|||||||
static void _timer5_capt_cb(void);
|
static void _timer5_capt_cb(void);
|
||||||
/* private variables to communicate with input capture isr */
|
/* private variables to communicate with input capture isr */
|
||||||
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
|
||||||
static volatile uint8_t _valid;
|
static volatile uint8_t _valid_channels;
|
||||||
|
|
||||||
/* override state */
|
/* override state */
|
||||||
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
|
||||||
|
@ -15,7 +15,7 @@ extern const HAL& hal;
|
|||||||
|
|
||||||
/* private variables to communicate with input capture isr */
|
/* private variables to communicate with input capture isr */
|
||||||
volatile uint16_t APM1RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
|
volatile uint16_t APM1RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
|
||||||
volatile uint8_t APM1RCInput::_valid = 0;
|
volatile uint8_t APM1RCInput::_valid_channels = 0;
|
||||||
|
|
||||||
/* private callback for input capture ISR */
|
/* private callback for input capture ISR */
|
||||||
void APM1RCInput::_timer4_capt_cb(void) {
|
void APM1RCInput::_timer4_capt_cb(void) {
|
||||||
@ -34,7 +34,7 @@ void APM1RCInput::_timer4_capt_cb(void) {
|
|||||||
if (pulse_width > 8000) {
|
if (pulse_width > 8000) {
|
||||||
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
||||||
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
||||||
_valid = channel_ctr;
|
_valid_channels = channel_ctr;
|
||||||
}
|
}
|
||||||
channel_ctr = 0;
|
channel_ctr = 0;
|
||||||
} else {
|
} else {
|
||||||
@ -42,7 +42,7 @@ void APM1RCInput::_timer4_capt_cb(void) {
|
|||||||
_pulse_capt[channel_ctr] = pulse_width;
|
_pulse_capt[channel_ctr] = pulse_width;
|
||||||
channel_ctr++;
|
channel_ctr++;
|
||||||
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
_valid = AVR_RC_INPUT_NUM_CHANNELS;
|
_valid_channels = AVR_RC_INPUT_NUM_CHANNELS;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -77,7 +77,7 @@ void APM1RCInput::init(void* _isrregistry) {
|
|||||||
TIMSK4 |= _BV(ICIE4);
|
TIMSK4 |= _BV(ICIE4);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t APM1RCInput::valid() { return _valid; }
|
uint8_t APM1RCInput::valid_channels() { return _valid_channels; }
|
||||||
|
|
||||||
|
|
||||||
/* constrain captured pulse to be between min and max pulsewidth. */
|
/* constrain captured pulse to be between min and max pulsewidth. */
|
||||||
@ -94,7 +94,7 @@ uint16_t APM1RCInput::read(uint8_t ch) {
|
|||||||
cli();
|
cli();
|
||||||
uint16_t capt = _pulse_capt[ch];
|
uint16_t capt = _pulse_capt[ch];
|
||||||
sei();
|
sei();
|
||||||
_valid = 0;
|
_valid_channels = 0;
|
||||||
/* scale _pulse_capt from 0.5us units to 1us units. */
|
/* scale _pulse_capt from 0.5us units to 1us units. */
|
||||||
uint16_t pulse = constrain_pulse(capt >> 1);
|
uint16_t pulse = constrain_pulse(capt >> 1);
|
||||||
/* Check for override */
|
/* Check for override */
|
||||||
@ -121,8 +121,8 @@ uint8_t APM1RCInput::read(uint16_t* periods, uint8_t len) {
|
|||||||
periods[i] = _override[i];
|
periods[i] = _override[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
uint8_t v = _valid;
|
uint8_t v = _valid_channels;
|
||||||
_valid = 0;
|
_valid_channels = 0;
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -139,7 +139,7 @@ bool APM1RCInput::set_override(uint8_t channel, int16_t override) {
|
|||||||
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
_override[channel] = override;
|
_override[channel] = override;
|
||||||
if (override != 0) {
|
if (override != 0) {
|
||||||
_valid = 1;
|
_valid_channels = 1;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -15,7 +15,7 @@ extern const HAL& hal;
|
|||||||
|
|
||||||
/* private variables to communicate with input capture isr */
|
/* private variables to communicate with input capture isr */
|
||||||
volatile uint16_t APM2RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
|
volatile uint16_t APM2RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
|
||||||
volatile uint8_t APM2RCInput::_valid = 0;
|
volatile uint8_t APM2RCInput::_valid_channels = 0;
|
||||||
|
|
||||||
/* private callback for input capture ISR */
|
/* private callback for input capture ISR */
|
||||||
void APM2RCInput::_timer5_capt_cb(void) {
|
void APM2RCInput::_timer5_capt_cb(void) {
|
||||||
@ -34,7 +34,7 @@ void APM2RCInput::_timer5_capt_cb(void) {
|
|||||||
if (pulse_width > 8000) {
|
if (pulse_width > 8000) {
|
||||||
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
// sync pulse detected. Pass through values if at least a minimum number of channels received
|
||||||
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
|
||||||
_valid = channel_ctr;
|
_valid_channels = channel_ctr;
|
||||||
}
|
}
|
||||||
channel_ctr = 0;
|
channel_ctr = 0;
|
||||||
} else {
|
} else {
|
||||||
@ -42,7 +42,7 @@ void APM2RCInput::_timer5_capt_cb(void) {
|
|||||||
_pulse_capt[channel_ctr] = pulse_width;
|
_pulse_capt[channel_ctr] = pulse_width;
|
||||||
channel_ctr++;
|
channel_ctr++;
|
||||||
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
_valid = AVR_RC_INPUT_NUM_CHANNELS;
|
_valid_channels = AVR_RC_INPUT_NUM_CHANNELS;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -77,7 +77,7 @@ void APM2RCInput::init(void* _isrregistry) {
|
|||||||
TIMSK5 |= _BV(ICIE5);
|
TIMSK5 |= _BV(ICIE5);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t APM2RCInput::valid() { return _valid; }
|
uint8_t APM2RCInput::valid_channels() { return _valid_channels; }
|
||||||
|
|
||||||
/* constrain captured pulse to be between min and max pulsewidth. */
|
/* constrain captured pulse to be between min and max pulsewidth. */
|
||||||
static inline uint16_t constrain_pulse(uint16_t p) {
|
static inline uint16_t constrain_pulse(uint16_t p) {
|
||||||
@ -94,7 +94,7 @@ uint16_t APM2RCInput::read(uint8_t ch) {
|
|||||||
cli();
|
cli();
|
||||||
uint16_t capt = _pulse_capt[ch];
|
uint16_t capt = _pulse_capt[ch];
|
||||||
sei();
|
sei();
|
||||||
_valid = 0;
|
_valid_channels = 0;
|
||||||
/* scale _pulse_capt from 0.5us units to 1us units. */
|
/* scale _pulse_capt from 0.5us units to 1us units. */
|
||||||
uint16_t pulse = constrain_pulse(capt >> 1);
|
uint16_t pulse = constrain_pulse(capt >> 1);
|
||||||
/* Check for override */
|
/* Check for override */
|
||||||
@ -121,8 +121,8 @@ uint8_t APM2RCInput::read(uint16_t* periods, uint8_t len) {
|
|||||||
periods[i] = _override[i];
|
periods[i] = _override[i];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
uint8_t v = _valid;
|
uint8_t v = _valid_channels;
|
||||||
_valid = 0;
|
_valid_channels = 0;
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -139,7 +139,7 @@ bool APM2RCInput::set_override(uint8_t channel, int16_t override) {
|
|||||||
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
|
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
|
||||||
_override[channel] = override;
|
_override[channel] = override;
|
||||||
if (override != 0) {
|
if (override != 0) {
|
||||||
_valid = 1;
|
_valid_channels = 1;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -12,7 +12,7 @@ void SITLRCInput::init(void* machtnichts)
|
|||||||
clear_overrides();
|
clear_overrides();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t SITLRCInput::valid() {
|
uint8_t SITLRCInput::valid_channels() {
|
||||||
return _sitlState->pwm_valid;
|
return _sitlState->pwm_valid;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -12,7 +12,7 @@ public:
|
|||||||
_sitlState = sitlState;
|
_sitlState = sitlState;
|
||||||
}
|
}
|
||||||
void init(void* machtnichts);
|
void init(void* machtnichts);
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
|
|
||||||
|
@ -8,7 +8,7 @@ EmptyRCInput::EmptyRCInput()
|
|||||||
void EmptyRCInput::init(void* machtnichts)
|
void EmptyRCInput::init(void* machtnichts)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
uint8_t EmptyRCInput::valid() {
|
uint8_t EmptyRCInput::valid_channels() {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -8,7 +8,7 @@ class Empty::EmptyRCInput : public AP_HAL::RCInput {
|
|||||||
public:
|
public:
|
||||||
EmptyRCInput();
|
EmptyRCInput();
|
||||||
void init(void* machtnichts);
|
void init(void* machtnichts);
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
|
|
||||||
|
@ -19,7 +19,7 @@ void PX4RCInput::init(void* unused)
|
|||||||
clear_overrides();
|
clear_overrides();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t PX4RCInput::valid()
|
uint8_t PX4RCInput::valid_channels()
|
||||||
{
|
{
|
||||||
return _rcin.timestamp != _last_read || _override_valid;
|
return _rcin.timestamp != _last_read || _override_valid;
|
||||||
}
|
}
|
||||||
|
@ -9,7 +9,7 @@
|
|||||||
class PX4::PX4RCInput : public AP_HAL::RCInput {
|
class PX4::PX4RCInput : public AP_HAL::RCInput {
|
||||||
public:
|
public:
|
||||||
void init(void* machtnichts);
|
void init(void* machtnichts);
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
|
|
||||||
|
@ -29,7 +29,7 @@ void SMACCMRCInput::init(void *unused)
|
|||||||
clear_overrides();
|
clear_overrides();
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t SMACCMRCInput::valid()
|
uint8_t SMACCMRCInput::valid_channels()
|
||||||
{
|
{
|
||||||
// If any of the overrides are positive, we have valid data.
|
// If any of the overrides are positive, we have valid data.
|
||||||
for (int i = 0; i < SMACCM_RCINPUT_CHANNELS; ++i)
|
for (int i = 0; i < SMACCM_RCINPUT_CHANNELS; ++i)
|
||||||
|
@ -10,7 +10,7 @@ class SMACCM::SMACCMRCInput : public AP_HAL::RCInput {
|
|||||||
public:
|
public:
|
||||||
SMACCMRCInput();
|
SMACCMRCInput();
|
||||||
void init(void *unused);
|
void init(void *unused);
|
||||||
uint8_t valid();
|
uint8_t valid_channels();
|
||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
uint8_t read(uint16_t* periods, uint8_t len);
|
uint8_t read(uint16_t* periods, uint8_t len);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user