AP_HAL: removed RCInput valid_channels() and added new_input() and num_channels()

the valid_channels() method was inconsistently implemented between
boards, and served two quite different purposes. It is clearer as two
functions
This commit is contained in:
Andrew Tridgell 2014-03-25 14:39:41 +11:00
parent 27dbf608c8
commit 6eee2421cc
21 changed files with 103 additions and 62 deletions

View File

@ -18,12 +18,14 @@ public:
virtual void init(void* implspecific) = 0;
/**
* Return the number of currently valid channels.
* Typically 0 (no valid radio channels) or 8 (implementation-defined)
* Could be less than or greater than 8 depending on your incoming radio
* or PPM stream
* Return true if there has been new input since the last read() call
*/
virtual uint8_t valid_channels() = 0;
virtual bool new_input() = 0;
/**
* Return the number of valid channels in the last read
*/
virtual uint8_t num_channels() = 0;
/* Read a single channel at a time */
virtual uint16_t read(uint8_t ch) = 0;

View File

@ -18,6 +18,12 @@
#define CH_10 9
#define CH_11 10
#define CH_12 11
#define CH_13 12
#define CH_14 13
#define CH_15 14
#define CH_16 15
#define CH_17 16
#define CH_18 17
#endif

View File

@ -17,13 +17,14 @@ public:
void init(void* isrregistry);
/**
* valid_channels():
* Return the number of currently valid channels.
* Typically 0 (no valid radio channels) or 8 (implementation-defined)
* Could be less than or greater than 8 depending on your incoming radio
* or PPM stream
* Return true if new input since the last read()
*/
uint8_t valid_channels();
bool new_input();
/**
* Return the number of input channels in last read()
*/
uint8_t num_channels();
/**
* read(uint8_t):
@ -58,7 +59,8 @@ private:
static void _timer4_capt_cb(void);
/* private variables to communicate with input capture isr */
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
static volatile uint8_t _valid_channels;
static volatile uint8_t _num_channels;
static volatile bool _new_input;
/* override state */
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];
@ -67,7 +69,8 @@ private:
class AP_HAL_AVR::APM2RCInput : public AP_HAL::RCInput {
/* Pass in a AP_HAL_AVR::ISRRegistry* as void*. */
void init(void* isrregistry);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);
bool set_overrides(int16_t *overrides, uint8_t len);
@ -78,7 +81,8 @@ private:
static void _timer5_capt_cb(void);
/* private variables to communicate with input capture isr */
static volatile uint16_t _pulse_capt[AVR_RC_INPUT_NUM_CHANNELS];
static volatile uint8_t _valid_channels;
static volatile uint8_t _num_channels;
static volatile bool _new_input;
/* override state */
uint16_t _override[AVR_RC_INPUT_NUM_CHANNELS];

View File

@ -15,7 +15,8 @@ extern const HAL& hal;
/* private variables to communicate with input capture isr */
volatile uint16_t APM1RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
volatile uint8_t APM1RCInput::_valid_channels = 0;
volatile uint8_t APM1RCInput::_num_channels = 0;
volatile bool APM1RCInput::_new_input = false;
/* private callback for input capture ISR */
void APM1RCInput::_timer4_capt_cb(void) {
@ -34,7 +35,8 @@ void APM1RCInput::_timer4_capt_cb(void) {
if (pulse_width > 8000) {
// sync pulse detected. Pass through values if at least a minimum number of channels received
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
_valid_channels = channel_ctr;
_num_channels = channel_ctr;
_new_input = true;
}
channel_ctr = 0;
} else {
@ -42,7 +44,8 @@ void APM1RCInput::_timer4_capt_cb(void) {
_pulse_capt[channel_ctr] = pulse_width;
channel_ctr++;
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
_valid_channels = AVR_RC_INPUT_NUM_CHANNELS;
_num_channels = AVR_RC_INPUT_NUM_CHANNELS;
_new_input = true;
}
}
}
@ -88,7 +91,9 @@ void APM1RCInput::init(void* _isrregistry) {
SREG = oldSREG;
}
uint8_t APM1RCInput::valid_channels() { return _valid_channels; }
bool APM1RCInput::new_input() { return _new_input; }
uint8_t APM1RCInput::num_channels() { return _num_channels; }
/* constrain captured pulse to be between min and max pulsewidth. */
@ -106,7 +111,7 @@ uint16_t APM1RCInput::read(uint8_t ch) {
cli();
uint16_t capt = _pulse_capt[ch];
SREG = oldSREG;
_valid_channels = 0;
_new_input = false;
/* scale _pulse_capt from 0.5us units to 1us units. */
uint16_t pulse = constrain_pulse(capt >> 1);
/* Check for override */
@ -134,9 +139,8 @@ uint8_t APM1RCInput::read(uint16_t* periods, uint8_t len) {
periods[i] = _override[i];
}
}
uint8_t v = _valid_channels;
_valid_channels = 0;
return v;
_new_input = false;
return _num_channels;
}
bool APM1RCInput::set_overrides(int16_t *overrides, uint8_t len) {
@ -152,7 +156,7 @@ bool APM1RCInput::set_override(uint8_t channel, int16_t override) {
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
_override[channel] = override;
if (override != 0) {
_valid_channels = 1;
_new_input = true;
return true;
}
}

View File

@ -15,7 +15,8 @@ extern const HAL& hal;
/* private variables to communicate with input capture isr */
volatile uint16_t APM2RCInput::_pulse_capt[AVR_RC_INPUT_NUM_CHANNELS] = {0};
volatile uint8_t APM2RCInput::_valid_channels = 0;
volatile uint8_t APM2RCInput::_num_channels = 0;
volatile bool APM2RCInput::_new_input = false;
/* private callback for input capture ISR */
void APM2RCInput::_timer5_capt_cb(void) {
@ -34,7 +35,8 @@ void APM2RCInput::_timer5_capt_cb(void) {
if (pulse_width > 8000) {
// sync pulse detected. Pass through values if at least a minimum number of channels received
if( channel_ctr >= AVR_RC_INPUT_MIN_CHANNELS ) {
_valid_channels = channel_ctr;
_num_channels = channel_ctr;
_new_input = true;
}
channel_ctr = 0;
} else {
@ -42,7 +44,8 @@ void APM2RCInput::_timer5_capt_cb(void) {
_pulse_capt[channel_ctr] = pulse_width;
channel_ctr++;
if (channel_ctr == AVR_RC_INPUT_NUM_CHANNELS) {
_valid_channels = AVR_RC_INPUT_NUM_CHANNELS;
_num_channels = AVR_RC_INPUT_NUM_CHANNELS;
_new_input = true;
}
}
}
@ -88,7 +91,8 @@ void APM2RCInput::init(void* _isrregistry) {
SREG = oldSREG;
}
uint8_t APM2RCInput::valid_channels() { return _valid_channels; }
bool APM2RCInput::new_input() { return _new_input; }
uint8_t APM2RCInput::num_channels() { return _num_channels; }
/* constrain captured pulse to be between min and max pulsewidth. */
static inline uint16_t constrain_pulse(uint16_t p) {
@ -106,7 +110,7 @@ uint16_t APM2RCInput::read(uint8_t ch) {
cli();
uint16_t capt = _pulse_capt[ch];
SREG = oldSREG;
_valid_channels = 0;
_new_input = false;
/* scale _pulse_capt from 0.5us units to 1us units. */
uint16_t pulse = constrain_pulse(capt >> 1);
/* Check for override */
@ -134,9 +138,7 @@ uint8_t APM2RCInput::read(uint16_t* periods, uint8_t len) {
periods[i] = _override[i];
}
}
uint8_t v = _valid_channels;
_valid_channels = 0;
return v;
return _num_channels;
}
bool APM2RCInput::set_overrides(int16_t *overrides, uint8_t len) {
@ -152,7 +154,7 @@ bool APM2RCInput::set_override(uint8_t channel, int16_t override) {
if (channel < AVR_RC_INPUT_NUM_CHANNELS) {
_override[channel] = override;
if (override != 0) {
_valid_channels = 1;
_new_input = true;
return true;
}
}

View File

@ -27,9 +27,9 @@ void multiread(AP_HAL::RCInput* in) {
void individualread(AP_HAL::RCInput* in) {
/* individual channel read method: */
uint8_t valid;
bool valid;
uint16_t channels[8];
valid = in->valid_channels();
valid = in->new_input();
for (int i = 0; i < 8; i++) {
channels[i] = in->read(i);
}

View File

@ -26,8 +26,8 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
/* individual channel read method: */
uint8_t valid;
valid = in->valid_channels();
bool valid;
valid = in->new_input();
for (int i = 0; i < 8; i++) {
channels[i] = in->read(i);
}

View File

@ -12,12 +12,12 @@ void SITLRCInput::init(void* machtnichts)
clear_overrides();
}
uint8_t SITLRCInput::valid_channels() {
return _sitlState->pwm_valid;
bool SITLRCInput::new_input() {
return _sitlState->new_rc_input;
}
uint16_t SITLRCInput::read(uint8_t ch) {
_sitlState->pwm_valid = false;
_sitlState->new_rc_input = false;
return _override[ch]? _override[ch] : _sitlState->pwm_input[ch];
}
@ -25,9 +25,8 @@ uint8_t SITLRCInput::read(uint16_t* periods, uint8_t len) {
for (uint8_t i=0; i<len; i++) {
periods[i] = _override[i]? _override[i] : _sitlState->pwm_input[i];
}
uint8_t v = _sitlState->pwm_valid;
_sitlState->pwm_valid = false;
return v;
_sitlState->new_rc_input = false;
return 8;
}
bool SITLRCInput::set_overrides(int16_t *overrides, uint8_t len) {

View File

@ -12,7 +12,8 @@ public:
_sitlState = sitlState;
}
void init(void* machtnichts);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels() { return 8; }
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);

View File

@ -73,7 +73,7 @@ SITL *SITL_State::_sitl;
uint16_t SITL_State::pwm_output[11];
uint16_t SITL_State::last_pwm_output[11];
uint16_t SITL_State::pwm_input[8];
bool SITL_State::pwm_valid;
bool SITL_State::new_rc_input;
// catch floating point exceptions
void SITL_State::_sig_fpe(int signum)
@ -263,7 +263,7 @@ void SITL_State::_timer_handler(int signum)
// simulate RC input at 50Hz
if (hal.scheduler->millis() - last_pwm_input >= 20 && _sitl->rc_fail == 0) {
last_pwm_input = hal.scheduler->millis();
pwm_valid = true;
new_rc_input = true;
}
/* check for packet from flight sim */

View File

@ -39,7 +39,7 @@ public:
static uint16_t pwm_output[11];
static uint16_t last_pwm_output[11];
static uint16_t pwm_input[8];
static bool pwm_valid;
static bool new_rc_input;
static void loop_hook(void);
uint16_t base_port(void) const { return _base_port; }

View File

@ -8,7 +8,11 @@ EmptyRCInput::EmptyRCInput()
void EmptyRCInput::init(void* machtnichts)
{}
uint8_t EmptyRCInput::valid_channels() {
bool EmptyRCInput::new_input() {
return false;
}
uint8_t EmptyRCInput::num_channels() {
return 0;
}

View File

@ -8,7 +8,8 @@ class Empty::EmptyRCInput : public AP_HAL::RCInput {
public:
EmptyRCInput();
void init(void* machtnichts);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);

View File

@ -127,9 +127,13 @@ void FLYMAPLERCInput::init(void* machtnichts)
timer_resume(tdev); // reenabled
}
uint8_t FLYMAPLERCInput::valid_channels() {
bool FLYMAPLERCInput::new_input() {
if ((hal.scheduler->millis() - _last_input_interrupt_time) > 50)
_valid_channels = 0; // Lost RC Input?
return _valid_channels != 0;
}
uint8_t FLYMAPLERCInput::num_channels() {
return _valid_channels;
}

View File

@ -29,7 +29,8 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLERCInput : public AP_HAL::RCInput {
public:
FLYMAPLERCInput();
void init(void* machtnichts);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);

View File

@ -11,8 +11,8 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
/* Multi-channel read method: */
uint8_t valid;
valid = in->valid_channels();
bool valid;
valid = in->new_input();
in->read(channels, 8);
hal.console->printf_P(
PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
@ -23,8 +23,8 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
/* individual channel read method: */
uint8_t valid;
valid = in->valid_channels();
bool valid;
valid = in->new_input();
for (int i = 0; i < 8; i++) {
channels[i] = in->read(i);
}

View File

@ -22,8 +22,8 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
/* individual channel read method: */
uint8_t valid;
valid = in->valid_channels();
bool valid;
valid = in->new_input();
for (int i = 0; i < 8; i++) {
channels[i] = in->read(i);
}

View File

@ -11,7 +11,11 @@ LinuxRCInput::LinuxRCInput()
void LinuxRCInput::init(void* machtnichts)
{}
uint8_t LinuxRCInput::valid_channels() {
bool LinuxRCInput::new_input() {
return false;
}
uint8_t LinuxRCInput::num_channels() {
return 0;
}

View File

@ -8,7 +8,8 @@ class Linux::LinuxRCInput : public AP_HAL::RCInput {
public:
LinuxRCInput();
void init(void* machtnichts);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);

View File

@ -20,7 +20,7 @@ void PX4RCInput::init(void* unused)
pthread_mutex_init(&rcin_mutex, NULL);
}
uint8_t PX4RCInput::valid_channels()
bool PX4RCInput::new_input()
{
pthread_mutex_lock(&rcin_mutex);
bool valid = _rcin.timestamp_last_signal != _last_read || _override_valid;
@ -28,6 +28,14 @@ uint8_t PX4RCInput::valid_channels()
return valid;
}
uint8_t PX4RCInput::num_channels()
{
pthread_mutex_lock(&rcin_mutex);
uint8_t n = _rcin.channel_count;
pthread_mutex_unlock(&rcin_mutex);
return n;
}
uint16_t PX4RCInput::read(uint8_t ch)
{
if (ch >= RC_INPUT_MAX_CHANNELS) {
@ -101,7 +109,7 @@ void PX4RCInput::_timer_tick(void)
orb_copy(ORB_ID(input_rc), _rc_sub, &_rcin);
pthread_mutex_unlock(&rcin_mutex);
}
// note, we rely on the vehicle code checking valid_channels()
// note, we rely on the vehicle code checking new_input()
// and a timeout for the last valid input to handle failsafe
perf_end(_perf_rcin);
}

View File

@ -10,7 +10,8 @@
class PX4::PX4RCInput : public AP_HAL::RCInput {
public:
void init(void* machtnichts);
uint8_t valid_channels();
bool new_input();
uint8_t num_channels();
uint16_t read(uint8_t ch);
uint8_t read(uint16_t* periods, uint8_t len);
@ -28,7 +29,6 @@ private:
uint64_t _last_read;
bool _override_valid;
perf_counter_t _perf_rcin;
pthread_mutex_t rcin_mutex;
};