mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Decouple failsafe from RX drivers.
This removes a number of FIXMEs regarding driver dependencies on the main code. The code to verify pulse lengths is now in computeRC which means that all RX drivers do not have to duplicate the pulse length checking code. This means that failsafe can be used to validate serial RX providers as well as PWM/PPM RX providers.
This commit is contained in:
parent
3ed979e88c
commit
6704ba40b5
12 changed files with 114 additions and 152 deletions
|
@ -4,14 +4,13 @@
|
||||||
#include "stdint.h"
|
#include "stdint.h"
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "gpio_common.h"
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
|
#include "timer_common.h"
|
||||||
|
|
||||||
#include "failsafe.h" // FIXME dependency into the main code from a driver
|
#include "pwm_mapping.h"
|
||||||
|
#include "pwm_rx.h"
|
||||||
#include "pwm_common.h"
|
#include "pwm_output.h"
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
|
||||||
static uint16_t failsafeThreshold = 985;
|
|
||||||
|
|
||||||
#define PULSE_1MS (1000) // 1ms pulse width
|
#define PULSE_1MS (1000) // 1ms pulse width
|
||||||
// #define PULSE_PERIOD (2500) // pulse period (400Hz)
|
// #define PULSE_PERIOD (2500) // pulse period (400Hz)
|
||||||
|
@ -75,7 +74,6 @@ static void ppmIRQHandler(TIM_TypeDef *tim)
|
||||||
static uint16_t now;
|
static uint16_t now;
|
||||||
static uint16_t last = 0;
|
static uint16_t last = 0;
|
||||||
static uint8_t chan = 0;
|
static uint8_t chan = 0;
|
||||||
static uint8_t GoodPulses;
|
|
||||||
|
|
||||||
if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
|
if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) {
|
||||||
last = now;
|
last = now;
|
||||||
|
@ -93,17 +91,10 @@ static void ppmIRQHandler(TIM_TypeDef *tim)
|
||||||
if (diff > 4000) {
|
if (diff > 4000) {
|
||||||
chan = 0;
|
chan = 0;
|
||||||
} else {
|
} else {
|
||||||
if (diff > PULSE_MIN && diff < PULSE_MAX && chan < 8) { // 750 to 2250 ms is our 'valid' channel range
|
if (chan < 8) {
|
||||||
Inputs[chan].capture = diff;
|
Inputs[chan].capture = diff;
|
||||||
if (chan < 4 && diff > failsafeThreshold)
|
|
||||||
GoodPulses |= (1 << chan); // if signal is valid - mark channel as OK
|
|
||||||
if (GoodPulses == 0x0F) { // If first four chanells have good pulses, clear FailSafe counter
|
|
||||||
GoodPulses = 0;
|
|
||||||
failsafe->vTable->validDataReceived();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
chan++;
|
chan++;
|
||||||
failsafe->vTable->reset();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -156,9 +147,6 @@ static void pwmIRQHandler(TIM_TypeDef *tim)
|
||||||
// switch state
|
// switch state
|
||||||
state->state = 0;
|
state->state = 0;
|
||||||
|
|
||||||
// ping failsafe
|
|
||||||
failsafe->vTable->reset();
|
|
||||||
|
|
||||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||||
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||||
TIM_ICInit(channel.tim, &TIM_ICInitStructure);
|
TIM_ICInit(channel.tim, &TIM_ICInitStructure);
|
||||||
|
@ -255,7 +243,7 @@ static void pwmInitializeInput(bool usePPM)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmInit(drv_pwm_config_t *init, failsafe_t *initialFailsafe)
|
void pwmInit(drv_pwm_config_t *init)
|
||||||
{
|
{
|
||||||
GPIO_InitTypeDef GPIO_InitStructure = { 0, };
|
GPIO_InitTypeDef GPIO_InitStructure = { 0, };
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, };
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, };
|
||||||
|
@ -263,8 +251,6 @@ void pwmInit(drv_pwm_config_t *init, failsafe_t *initialFailsafe)
|
||||||
|
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
failsafe = initialFailsafe;
|
|
||||||
|
|
||||||
// Inputs
|
// Inputs
|
||||||
|
|
||||||
// RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration]
|
// RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration]
|
||||||
|
|
|
@ -15,11 +15,6 @@
|
||||||
|
|
||||||
|
|
||||||
#define PULSE_1MS (1000) // 1ms pulse width
|
#define PULSE_1MS (1000) // 1ms pulse width
|
||||||
#define PULSE_MIN (750) // minimum PWM pulse width which is considered valid
|
|
||||||
#define PULSE_MAX (2250) // maximum PWM pulse width which is considered valid
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAX_INPUTS 8
|
#define MAX_INPUTS 8
|
||||||
|
|
||||||
|
|
|
@ -9,15 +9,10 @@
|
||||||
#include "gpio_common.h"
|
#include "gpio_common.h"
|
||||||
#include "timer_common.h"
|
#include "timer_common.h"
|
||||||
|
|
||||||
#include "failsafe.h" // FIXME dependency into the main code from a driver
|
|
||||||
|
|
||||||
#include "pwm_mapping.h"
|
#include "pwm_mapping.h"
|
||||||
|
|
||||||
#include "pwm_rx.h"
|
#include "pwm_rx.h"
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
|
||||||
failsafeConfig_t *failsafeConfig;
|
|
||||||
|
|
||||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity); // from pwm_output.c
|
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity); // from pwm_output.c
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -41,17 +36,6 @@ static pwmInputPort_t pwmInputPorts[MAX_PWM_INPUT_PORTS];
|
||||||
|
|
||||||
static uint16_t captures[MAX_PWM_INPUT_PORTS];
|
static uint16_t captures[MAX_PWM_INPUT_PORTS];
|
||||||
|
|
||||||
static void failsafeCheck(uint8_t channel, uint16_t pulseDuration)
|
|
||||||
{
|
|
||||||
static uint8_t goodChannelMask;
|
|
||||||
|
|
||||||
if (channel < 4 && pulseDuration > failsafeConfig->failsafe_detect_threshold)
|
|
||||||
goodChannelMask |= (1 << channel); // if signal is valid - mark channel as OK
|
|
||||||
if (goodChannelMask == 0x0F) { // If first four channels have good pulses, clear FailSafe counter
|
|
||||||
goodChannelMask = 0;
|
|
||||||
failsafe->vTable->validDataReceived();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void ppmCallback(uint8_t port, captureCompare_t capture)
|
static void ppmCallback(uint8_t port, captureCompare_t capture)
|
||||||
{
|
{
|
||||||
|
@ -68,9 +52,8 @@ static void ppmCallback(uint8_t port, captureCompare_t capture)
|
||||||
if (diff > 2700) { // Per http://www.rcgroups.com/forums/showpost.php?p=21996147&postcount=3960 "So, if you use 2.5ms or higher as being the reset for the PPM stream start, you will be fine. I use 2.7ms just to be safe."
|
if (diff > 2700) { // Per http://www.rcgroups.com/forums/showpost.php?p=21996147&postcount=3960 "So, if you use 2.5ms or higher as being the reset for the PPM stream start, you will be fine. I use 2.7ms just to be safe."
|
||||||
chan = 0;
|
chan = 0;
|
||||||
} else {
|
} else {
|
||||||
if (diff > PULSE_MIN && diff < PULSE_MAX && chan < MAX_PWM_INPUT_PORTS) { // 750 to 2250 ms is our 'valid' channel range
|
if (chan < MAX_PWM_INPUT_PORTS) {
|
||||||
captures[chan] = diff;
|
captures[chan] = diff;
|
||||||
failsafeCheck(chan, diff);
|
|
||||||
}
|
}
|
||||||
chan++;
|
chan++;
|
||||||
}
|
}
|
||||||
|
@ -87,12 +70,11 @@ static void pwmCallback(uint8_t port, captureCompare_t capture)
|
||||||
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
|
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Falling);
|
||||||
} else {
|
} else {
|
||||||
pwmInputPort->fall = capture;
|
pwmInputPort->fall = capture;
|
||||||
// compute capture
|
|
||||||
|
// compute and store capture
|
||||||
pwmInputPort->capture = pwmInputPort->fall - pwmInputPort->rise;
|
pwmInputPort->capture = pwmInputPort->fall - pwmInputPort->rise;
|
||||||
if (pwmInputPort->capture > PULSE_MIN && pwmInputPort->capture < PULSE_MAX) { // valid pulse width
|
captures[pwmInputPort->channel] = pwmInputPort->capture;
|
||||||
captures[pwmInputPort->channel] = pwmInputPort->capture;
|
|
||||||
failsafeCheck(pwmInputPort->channel, pwmInputPort->capture);
|
|
||||||
}
|
|
||||||
// switch state
|
// switch state
|
||||||
pwmInputPort->state = 0;
|
pwmInputPort->state = 0;
|
||||||
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
|
pwmICConfig(timerHardware->tim, timerHardware->channel, TIM_ICPolarity_Rising);
|
||||||
|
@ -164,8 +146,3 @@ uint16_t pwmRead(uint8_t channel)
|
||||||
return captures[channel];
|
return captures[channel];
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmRxInit(failsafe_t *initialFailsafe, failsafeConfig_t *initialFailsafeConfig)
|
|
||||||
{
|
|
||||||
failsafe = initialFailsafe;
|
|
||||||
failsafeConfig = initialFailsafeConfig;
|
|
||||||
}
|
|
||||||
|
|
|
@ -89,32 +89,51 @@ void updateState(void)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
if (hasTimerElapsed()) {
|
if (!hasTimerElapsed()) {
|
||||||
|
return;
|
||||||
if (shouldForceLanding(f.ARMED)) { // Stabilize, and set Throttle to specified level
|
|
||||||
for (i = 0; i < 3; i++) {
|
|
||||||
rcData[i] = rxConfig->midrc; // after specified guard time after RC signal is lost (in 0.1sec)
|
|
||||||
}
|
|
||||||
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
|
||||||
failsafe.events++;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (shouldHaveCausedLandingByNow() || !f.ARMED) {
|
|
||||||
failsafeAvoidRearm();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (shouldForceLanding(f.ARMED)) { // Stabilize, and set Throttle to specified level
|
||||||
|
for (i = 0; i < 3; i++) {
|
||||||
|
rcData[i] = rxConfig->midrc; // after specified guard time after RC signal is lost (in 0.1sec)
|
||||||
|
}
|
||||||
|
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
|
||||||
|
failsafe.events++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (shouldHaveCausedLandingByNow() || !f.ARMED) {
|
||||||
|
failsafeAvoidRearm();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void incrementCounter(void)
|
||||||
|
{
|
||||||
failsafe.counter++;
|
failsafe.counter++;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void failsafeCheckPulse(uint8_t channel, uint16_t pulseDuration)
|
||||||
|
{
|
||||||
|
static uint8_t goodChannelMask;
|
||||||
|
|
||||||
|
if (channel < 4 && pulseDuration > failsafeConfig->failsafe_detect_threshold)
|
||||||
|
goodChannelMask |= (1 << channel); // if signal is valid - mark channel as OK
|
||||||
|
if (goodChannelMask == 0x0F) { // If first four channels have good pulses, clear FailSafe counter
|
||||||
|
goodChannelMask = 0;
|
||||||
|
onValidDataReceived();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
const failsafeVTable_t failsafeVTable[] = {
|
const failsafeVTable_t failsafeVTable[] = {
|
||||||
{
|
{
|
||||||
reset,
|
reset,
|
||||||
onValidDataReceived,
|
|
||||||
shouldForceLanding,
|
shouldForceLanding,
|
||||||
hasTimerElapsed,
|
hasTimerElapsed,
|
||||||
shouldHaveCausedLandingByNow,
|
shouldHaveCausedLandingByNow,
|
||||||
|
incrementCounter,
|
||||||
updateState,
|
updateState,
|
||||||
isIdle
|
isIdle,
|
||||||
|
failsafeCheckPulse
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -9,12 +9,13 @@ typedef struct failsafeConfig_s {
|
||||||
|
|
||||||
typedef struct failsafeVTable_s {
|
typedef struct failsafeVTable_s {
|
||||||
void (*reset)(void);
|
void (*reset)(void);
|
||||||
void (*validDataReceived)(void);
|
|
||||||
bool (*shouldForceLanding)(bool armed);
|
bool (*shouldForceLanding)(bool armed);
|
||||||
bool (*hasTimerElapsed)(void);
|
bool (*hasTimerElapsed)(void);
|
||||||
bool (*shouldHaveCausedLandingByNow)(void);
|
bool (*shouldHaveCausedLandingByNow)(void);
|
||||||
|
void (*incrementCounter)(void);
|
||||||
void (*updateState)(void);
|
void (*updateState)(void);
|
||||||
bool (*isIdle)(void);
|
bool (*isIdle)(void);
|
||||||
|
void (*checkPulse)(uint8_t channel, uint16_t pulseDuration);
|
||||||
|
|
||||||
} failsafeVTable_t;
|
} failsafeVTable_t;
|
||||||
|
|
||||||
|
|
|
@ -57,7 +57,6 @@ void initTelemetry(serialPorts_t *serialPorts);
|
||||||
void serialInit(serialConfig_t *initialSerialConfig);
|
void serialInit(serialConfig_t *initialSerialConfig);
|
||||||
failsafe_t* failsafeInit(rxConfig_t *intialRxConfig);
|
failsafe_t* failsafeInit(rxConfig_t *intialRxConfig);
|
||||||
void pwmInit(drv_pwm_config_t *init);
|
void pwmInit(drv_pwm_config_t *init);
|
||||||
void pwmRxInit(failsafe_t *initialFailsafe, failsafeConfig_t *initialFailsafeConfig);
|
|
||||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
||||||
void buzzerInit(failsafe_t *initialFailsafe);
|
void buzzerInit(failsafe_t *initialFailsafe);
|
||||||
void gpsInit(uint8_t baudrateIndex, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
void gpsInit(uint8_t baudrateIndex, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
||||||
|
@ -191,7 +190,6 @@ int main(void)
|
||||||
#ifndef FY90Q
|
#ifndef FY90Q
|
||||||
timerInit();
|
timerInit();
|
||||||
#endif
|
#endif
|
||||||
pwmRxInit(failsafe, ¤tProfile.failsafeConfig);
|
|
||||||
pwmInit(&pwm_params);
|
pwmInit(&pwm_params);
|
||||||
|
|
||||||
rxInit(&masterConfig.rxConfig, failsafe);
|
rxInit(&masterConfig.rxConfig, failsafe);
|
||||||
|
|
108
src/rx_common.c
108
src/rx_common.c
|
@ -18,11 +18,11 @@
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
|
|
||||||
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *failsafe, rcReadRawDataPtr *callback);
|
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||||
void sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback);
|
void sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||||
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback);
|
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||||
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback);
|
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||||
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback);
|
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||||
|
|
||||||
const char rcChannelLetters[] = "AERT1234";
|
const char rcChannelLetters[] = "AERT1234";
|
||||||
|
|
||||||
|
@ -30,13 +30,19 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
|
|
||||||
#define PPM_AND_PWM_SAMPLE_COUNT 4
|
#define PPM_AND_PWM_SAMPLE_COUNT 4
|
||||||
|
|
||||||
|
#define PULSE_MIN 750 // minimum PWM pulse width which is considered valid
|
||||||
|
#define PULSE_MAX 2250 // maximum PWM pulse width which is considered valid
|
||||||
|
|
||||||
|
|
||||||
rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers)
|
||||||
|
|
||||||
rxRuntimeConfig_t rxRuntimeConfig;
|
rxRuntimeConfig_t rxRuntimeConfig;
|
||||||
|
|
||||||
void serialRxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
void serialRxInit(rxConfig_t *rxConfig);
|
||||||
|
|
||||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe)
|
failsafe_t *failsafe;
|
||||||
|
|
||||||
|
void rxInit(rxConfig_t *rxConfig, failsafe_t *initialFailsafe)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
|
@ -44,28 +50,30 @@ void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe)
|
||||||
rcData[i] = rxConfig->midrc;
|
rcData[i] = rxConfig->midrc;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
failsafe = initialFailsafe;
|
||||||
|
|
||||||
if (feature(FEATURE_SERIALRX)) {
|
if (feature(FEATURE_SERIALRX)) {
|
||||||
serialRxInit(rxConfig, failsafe);
|
serialRxInit(rxConfig);
|
||||||
} else {
|
} else {
|
||||||
rxPwmInit(&rxRuntimeConfig, failsafe, &rcReadRawFunc);
|
rxPwmInit(&rxRuntimeConfig, &rcReadRawFunc);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialRxInit(rxConfig_t *rxConfig, failsafe_t *failsafe)
|
void serialRxInit(rxConfig_t *rxConfig)
|
||||||
{
|
{
|
||||||
switch (rxConfig->serialrx_type) {
|
switch (rxConfig->serialrx_type) {
|
||||||
case SERIALRX_SPEKTRUM1024:
|
case SERIALRX_SPEKTRUM1024:
|
||||||
case SERIALRX_SPEKTRUM2048:
|
case SERIALRX_SPEKTRUM2048:
|
||||||
spektrumInit(rxConfig, &rxRuntimeConfig, failsafe, &rcReadRawFunc);
|
spektrumInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||||
break;
|
break;
|
||||||
case SERIALRX_SBUS:
|
case SERIALRX_SBUS:
|
||||||
sbusInit(rxConfig, &rxRuntimeConfig, failsafe, &rcReadRawFunc);
|
sbusInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||||
break;
|
break;
|
||||||
case SERIALRX_SUMD:
|
case SERIALRX_SUMD:
|
||||||
sumdInit(rxConfig, &rxRuntimeConfig, failsafe, &rcReadRawFunc);
|
sumdInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||||
break;
|
break;
|
||||||
case SERIALRX_MSP:
|
case SERIALRX_MSP:
|
||||||
rxMspInit(rxConfig, &rxRuntimeConfig, failsafe, &rcReadRawFunc);
|
rxMspInit(rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -93,46 +101,52 @@ uint8_t calculateChannelRemapping(uint8_t *rcmap, uint8_t channelToRemap) {
|
||||||
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
void computeRC(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
{
|
{
|
||||||
uint8_t chan;
|
uint8_t chan;
|
||||||
|
static int16_t rcSamples[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT], rcDataMean[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT];
|
||||||
|
static uint8_t rcSampleIndex = 0;
|
||||||
|
uint8_t currentSampleIndex;
|
||||||
|
|
||||||
if (feature(FEATURE_SERIALRX)) {
|
if (feature(FEATURE_FAILSAFE)) {
|
||||||
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
|
failsafe->vTable->incrementCounter();
|
||||||
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
|
}
|
||||||
rcData[chan] = rcReadRawFunc(rxRuntimeConfig, rawChannel);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
static int16_t rcSamples[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT], rcDataMean[MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT];
|
|
||||||
static uint8_t rcSampleIndex = 0;
|
|
||||||
uint8_t a;
|
|
||||||
|
|
||||||
|
if (!feature(FEATURE_SERIALRX)) {
|
||||||
rcSampleIndex++;
|
rcSampleIndex++;
|
||||||
uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
|
currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
|
||||||
|
}
|
||||||
|
|
||||||
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
|
for (chan = 0; chan < MAX_SUPPORTED_RC_PPM_AND_PWM_CHANNEL_COUNT; chan++) {
|
||||||
|
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
|
||||||
|
|
||||||
uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, chan);
|
// sample the channel
|
||||||
|
uint16_t sample = rcReadRawFunc(rxRuntimeConfig, rawChannel);
|
||||||
|
|
||||||
// sample the channel
|
if (feature(FEATURE_FAILSAFE)) {
|
||||||
uint16_t sample = rcReadRawFunc(rxRuntimeConfig, rawChannel);
|
failsafe->vTable->checkPulse(rawChannel, sample);
|
||||||
|
|
||||||
// validate the range
|
|
||||||
if (sample < 750 || sample > 2250)
|
|
||||||
sample = rxConfig->midrc;
|
|
||||||
|
|
||||||
rcSamples[chan][currentSampleIndex] = sample;
|
|
||||||
|
|
||||||
// compute the average of recent samples
|
|
||||||
rcDataMean[chan] = 0;
|
|
||||||
for (a = 0; a < PPM_AND_PWM_SAMPLE_COUNT; a++)
|
|
||||||
rcDataMean[chan] += rcSamples[chan][a];
|
|
||||||
|
|
||||||
rcDataMean[chan] = (rcDataMean[chan] + 2) / PPM_AND_PWM_SAMPLE_COUNT;
|
|
||||||
|
|
||||||
|
|
||||||
if (rcDataMean[chan] < rcData[chan] - 3)
|
|
||||||
rcData[chan] = rcDataMean[chan] + 2;
|
|
||||||
if (rcDataMean[chan] > rcData[chan] + 3)
|
|
||||||
rcData[chan] = rcDataMean[chan] - 2;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// validate the range
|
||||||
|
if (sample < PULSE_MIN || sample > PULSE_MAX)
|
||||||
|
sample = rxConfig->midrc;
|
||||||
|
|
||||||
|
if (feature(FEATURE_SERIALRX)) {
|
||||||
|
rcData[chan] = sample;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
// update the recent samples and compute the average of them
|
||||||
|
rcSamples[chan][currentSampleIndex] = sample;
|
||||||
|
rcDataMean[chan] = 0;
|
||||||
|
|
||||||
|
uint8_t sampleIndex;
|
||||||
|
for (sampleIndex = 0; sampleIndex < PPM_AND_PWM_SAMPLE_COUNT; sampleIndex++)
|
||||||
|
rcDataMean[chan] += rcSamples[chan][sampleIndex];
|
||||||
|
|
||||||
|
rcDataMean[chan] = (rcDataMean[chan] + 2) / PPM_AND_PWM_SAMPLE_COUNT;
|
||||||
|
|
||||||
|
if (rcDataMean[chan] < rcData[chan] - 3)
|
||||||
|
rcData[chan] = rcDataMean[chan] + 2;
|
||||||
|
if (rcDataMean[chan] > rcData[chan] + 3)
|
||||||
|
rcData[chan] = rcDataMean[chan] - 2;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -9,13 +9,9 @@
|
||||||
#include "drivers/serial_uart_common.h"
|
#include "drivers/serial_uart_common.h"
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
|
|
||||||
#include "failsafe.h"
|
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
#include "rx_msp.h"
|
#include "rx_msp.h"
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
|
||||||
|
|
||||||
static bool rxMspFrameDone = false;
|
static bool rxMspFrameDone = false;
|
||||||
|
|
||||||
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
|
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
|
||||||
|
@ -31,16 +27,14 @@ void rxMspFrameRecieve(void)
|
||||||
bool rxMspFrameComplete(void)
|
bool rxMspFrameComplete(void)
|
||||||
{
|
{
|
||||||
if (rxMspFrameDone) {
|
if (rxMspFrameDone) {
|
||||||
failsafe->vTable->reset();
|
|
||||||
rxMspFrameDone = false;
|
rxMspFrameDone = false;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)
|
void rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
{
|
{
|
||||||
failsafe = initialFailsafe;
|
|
||||||
if (callback)
|
if (callback)
|
||||||
*callback = rxMspReadRawRC;
|
*callback = rxMspReadRawRC;
|
||||||
}
|
}
|
||||||
|
|
|
@ -10,8 +10,6 @@
|
||||||
|
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
|
|
||||||
#include "failsafe.h"
|
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
#include "rx_pwm.h"
|
#include "rx_pwm.h"
|
||||||
|
|
||||||
|
@ -20,7 +18,7 @@ static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
|
||||||
return pwmRead(chan);
|
return pwmRead(chan);
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)
|
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
{
|
{
|
||||||
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
|
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
|
||||||
*callback = pwmReadRawRC;
|
*callback = pwmReadRawRC;
|
||||||
|
|
|
@ -9,8 +9,6 @@
|
||||||
#include "drivers/serial_uart_common.h"
|
#include "drivers/serial_uart_common.h"
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
|
|
||||||
#include "failsafe.h"
|
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
#include "rx_sbus.h"
|
#include "rx_sbus.h"
|
||||||
|
|
||||||
|
@ -27,12 +25,9 @@ static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||||
|
|
||||||
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
|
||||||
void sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)
|
|
||||||
{
|
{
|
||||||
int b;
|
int b;
|
||||||
failsafe = initialFailsafe;
|
|
||||||
|
|
||||||
//rxConfig = initialRxConfig;
|
//rxConfig = initialRxConfig;
|
||||||
|
|
||||||
|
@ -99,7 +94,6 @@ bool sbusFrameComplete(void)
|
||||||
{
|
{
|
||||||
if (sbusFrameDone) {
|
if (sbusFrameDone) {
|
||||||
if (!((sbus.in[22] >> 3) & 0x0001)) { // failsave flag
|
if (!((sbus.in[22] >> 3) & 0x0001)) { // failsave flag
|
||||||
failsafe->vTable->reset();
|
|
||||||
sbusChannelData[0] = sbus.msg.chan0;
|
sbusChannelData[0] = sbus.msg.chan0;
|
||||||
sbusChannelData[1] = sbus.msg.chan1;
|
sbusChannelData[1] = sbus.msg.chan1;
|
||||||
sbusChannelData[2] = sbus.msg.chan2;
|
sbusChannelData[2] = sbus.msg.chan2;
|
||||||
|
|
|
@ -9,8 +9,6 @@
|
||||||
#include "drivers/serial_uart_common.h"
|
#include "drivers/serial_uart_common.h"
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
|
|
||||||
#include "failsafe.h"
|
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
#include "rx_spektrum.h"
|
#include "rx_spektrum.h"
|
||||||
|
|
||||||
|
@ -33,12 +31,8 @@ volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
|
||||||
static void spektrumDataReceive(uint16_t c);
|
static void spektrumDataReceive(uint16_t c);
|
||||||
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
|
||||||
void spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)
|
|
||||||
{
|
{
|
||||||
failsafe = initialFailsafe;
|
|
||||||
|
|
||||||
switch (rxConfig->serialrx_type) {
|
switch (rxConfig->serialrx_type) {
|
||||||
case SERIALRX_SPEKTRUM2048:
|
case SERIALRX_SPEKTRUM2048:
|
||||||
// 11 bit frames
|
// 11 bit frames
|
||||||
|
@ -77,7 +71,6 @@ static void spektrumDataReceive(uint16_t c)
|
||||||
spekFrame[spekFramePosition] = (uint8_t)c;
|
spekFrame[spekFramePosition] = (uint8_t)c;
|
||||||
if (spekFramePosition == SPEK_FRAME_SIZE - 1) {
|
if (spekFramePosition == SPEK_FRAME_SIZE - 1) {
|
||||||
rcFrameComplete = true;
|
rcFrameComplete = true;
|
||||||
failsafe->vTable->reset();
|
|
||||||
} else {
|
} else {
|
||||||
spekFramePosition++;
|
spekFramePosition++;
|
||||||
}
|
}
|
||||||
|
|
|
@ -9,8 +9,6 @@
|
||||||
#include "drivers/serial_uart_common.h"
|
#include "drivers/serial_uart_common.h"
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
|
|
||||||
#include "failsafe.h"
|
|
||||||
|
|
||||||
#include "rx_common.h"
|
#include "rx_common.h"
|
||||||
#include "rx_sumd.h"
|
#include "rx_sumd.h"
|
||||||
|
|
||||||
|
@ -26,12 +24,8 @@ static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
|
||||||
|
|
||||||
static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
|
static uint32_t sumdChannelData[SUMD_MAX_CHANNEL];
|
||||||
|
|
||||||
failsafe_t *failsafe;
|
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
|
||||||
void sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, failsafe_t *initialFailsafe, rcReadRawDataPtr *callback)
|
|
||||||
{
|
{
|
||||||
failsafe = initialFailsafe;
|
|
||||||
|
|
||||||
serialPorts.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX);
|
serialPorts.rcvrport = uartOpen(USART2, sumdDataReceive, 115200, MODE_RX);
|
||||||
if (callback)
|
if (callback)
|
||||||
*callback = sumdReadRawRC;
|
*callback = sumdReadRawRC;
|
||||||
|
@ -78,7 +72,6 @@ bool sumdFrameComplete(void)
|
||||||
if (sumdFrameDone) {
|
if (sumdFrameDone) {
|
||||||
sumdFrameDone = false;
|
sumdFrameDone = false;
|
||||||
if (sumd[1] == 0x01) {
|
if (sumd[1] == 0x01) {
|
||||||
failsafe->vTable->reset();
|
|
||||||
if (sumdSize > SUMD_MAX_CHANNEL)
|
if (sumdSize > SUMD_MAX_CHANNEL)
|
||||||
sumdSize = SUMD_MAX_CHANNEL;
|
sumdSize = SUMD_MAX_CHANNEL;
|
||||||
for (b = 0; b < sumdSize; b++)
|
for (b = 0; b < sumdSize; b++)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue