mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: tidy up frontend/backend split
This commit is contained in:
parent
ff5e00da32
commit
d6b9ab7756
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#include "AP_RCProtocol.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
AP_RCProtocol_Backend::AP_RCProtocol_Backend(AP_RCProtocol &_frontend) :
|
||||
frontend(_frontend),
|
||||
|
@ -43,3 +44,15 @@ uint16_t AP_RCProtocol_Backend::read(uint8_t chan)
|
|||
return _pwm_values[chan];
|
||||
}
|
||||
|
||||
/*
|
||||
provide input from a backend
|
||||
*/
|
||||
void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool in_failsafe)
|
||||
{
|
||||
num_values = MIN(num_values, MAX_RCIN_CHANNELS);
|
||||
memcpy(_pwm_values, values, num_values*sizeof(uint16_t));
|
||||
_num_channels = num_values;
|
||||
if (!in_failsafe) {
|
||||
rc_input_count++;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -29,11 +29,15 @@ public:
|
|||
uint16_t read(uint8_t chan);
|
||||
bool new_input();
|
||||
uint8_t num_channels();
|
||||
|
||||
protected:
|
||||
void add_input(uint8_t num_channels, uint16_t *values, bool in_failsafe);
|
||||
|
||||
private:
|
||||
AP_RCProtocol &frontend;
|
||||
unsigned int rc_input_count;
|
||||
unsigned int last_rc_input_count;
|
||||
|
||||
uint16_t _pwm_values[MAX_RCIN_CHANNELS] = {0};
|
||||
uint16_t _pwm_values[MAX_RCIN_CHANNELS];
|
||||
uint8_t _num_channels;
|
||||
};
|
||||
};
|
||||
|
|
|
@ -14,12 +14,16 @@
|
|||
*
|
||||
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
||||
*/
|
||||
/*
|
||||
with thanks to PX4 dsm.c for DSM decoding approach
|
||||
*/
|
||||
#include "AP_RCProtocol_DSM.h"
|
||||
|
||||
//#define DEBUG
|
||||
// #define DEBUG
|
||||
|
||||
#ifdef DEBUG
|
||||
# define debug(fmt, args...) printf(fmt "\n", ##args)
|
||||
extern const AP_HAL::HAL& hal;
|
||||
# define debug(fmt, args...) hal.console->printf(fmt "\n", ##args)
|
||||
#else
|
||||
# define debug(fmt, args...) do {} while(0)
|
||||
#endif
|
||||
|
@ -81,11 +85,7 @@ void AP_RCProtocol_DSM::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
uint16_t num_values=0;
|
||||
if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, 8) &&
|
||||
num_values >= MIN_RCIN_CHANNELS) {
|
||||
for (i=0; i<num_values; i++) {
|
||||
_pwm_values[i] = values[i];
|
||||
}
|
||||
_num_channels = num_values;
|
||||
rc_input_count++;
|
||||
add_input(num_values, values, false);
|
||||
}
|
||||
}
|
||||
memset(&dsm_state, 0, sizeof(dsm_state));
|
||||
|
@ -244,17 +244,18 @@ void AP_RCProtocol_DSM::dsm_guess_format(bool reset, const uint8_t dsm_frame[16]
|
|||
bool AP_RCProtocol_DSM::dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16],
|
||||
uint16_t *values, uint16_t *num_values, uint16_t max_values)
|
||||
{
|
||||
/*
|
||||
#if 0
|
||||
debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
|
||||
dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
|
||||
dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
|
||||
*/
|
||||
#endif
|
||||
/*
|
||||
* If we have lost signal for at least a second, reset the
|
||||
* format guessing heuristic.
|
||||
*/
|
||||
if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
|
||||
if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0)) {
|
||||
dsm_guess_format(true, dsm_frame);
|
||||
}
|
||||
|
||||
/* we have received something we think is a dsm_frame */
|
||||
dsm_last_frame_time = frame_time;
|
||||
|
|
|
@ -27,11 +27,7 @@ void AP_RCProtocol_PPMSum::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
// a long pulse indicates the end of a frame. Reset the
|
||||
// channel counter so next pulse is channel 0
|
||||
if (ppm_state._channel_counter >= MIN_RCIN_CHANNELS) {
|
||||
for (uint8_t i=0; i<ppm_state._channel_counter; i++) {
|
||||
_pwm_values[i] = ppm_state._pulse_capt[i];
|
||||
}
|
||||
_num_channels = ppm_state._channel_counter;
|
||||
rc_input_count++;
|
||||
add_input(ppm_state._channel_counter, ppm_state._pulse_capt, false);
|
||||
}
|
||||
ppm_state._channel_counter = 0;
|
||||
return;
|
||||
|
@ -58,11 +54,7 @@ void AP_RCProtocol_PPMSum::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
// if we have reached the maximum supported channels then
|
||||
// mark as unsynchronised, so we wait for a wide pulse
|
||||
if (ppm_state._channel_counter >= MAX_RCIN_CHANNELS) {
|
||||
for (uint8_t i=0; i<ppm_state._channel_counter; i++) {
|
||||
_pwm_values[i] = ppm_state._pulse_capt[i];
|
||||
}
|
||||
_num_channels = ppm_state._channel_counter;
|
||||
rc_input_count++;
|
||||
add_input(ppm_state._channel_counter, ppm_state._pulse_capt, false);
|
||||
ppm_state._channel_counter = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -267,13 +267,7 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
&sbus_failsafe, &sbus_frame_drop,
|
||||
MAX_RCIN_CHANNELS) &&
|
||||
num_values >= MIN_RCIN_CHANNELS) {
|
||||
for (i=0; i<num_values; i++) {
|
||||
_pwm_values[i] = values[i];
|
||||
}
|
||||
_num_channels = num_values;
|
||||
if (!sbus_failsafe) {
|
||||
rc_input_count++;
|
||||
}
|
||||
add_input(num_values, values, sbus_failsafe);
|
||||
}
|
||||
goto reset;
|
||||
} else if (bits_s1 > 12) {
|
||||
|
|
Loading…
Reference in New Issue