1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Added rxConfig parameter group

This commit is contained in:
Martin Budden 2017-01-03 21:57:52 +00:00
parent 261d16307f
commit 4f08c99401
32 changed files with 372 additions and 394 deletions

View file

@ -52,8 +52,6 @@
#include "io/serial.h"
#include "io/servos.h"
#include "rx/rx.h"
#include "sensors/sensors.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
@ -69,7 +67,6 @@
#define batteryConfig(x) (&masterConfig.batteryConfig)
#define gpsConfig(x) (&masterConfig.gpsConfig)
#define navConfig(x) (&masterConfig.navConfig)
#define rxConfig(x) (&masterConfig.rxConfig)
#define armingConfig(x) (&masterConfig.armingConfig)
#define mixerConfig(x) (&masterConfig.mixerConfig)
#define failsafeConfig(x) (&masterConfig.failsafeConfig)
@ -146,7 +143,6 @@ typedef struct master_s {
navConfig_t navConfig;
#endif
rxConfig_t rxConfig;
pwmRxConfig_t pwmRxConfig;
armingConfig_t armingConfig;

View file

@ -39,7 +39,7 @@
//#define PG_SERVO_MIXER 21
//#define PG_IMU_CONFIG 22
//#define PG_PROFILE_SELECTION 23
//#define PG_RX_CONFIG 24
#define PG_RX_CONFIG 24
//#define PG_RC_CONTROLS_CONFIG 25
//#define PG_MOTOR_3D_CONFIG 26
//#define PG_LED_STRIP_CONFIG 27
@ -58,8 +58,8 @@
#define PG_COMPASS_CONFIG 40
//#define PG_MODE_ACTIVATION_PROFILE 41
//#define PG_SERVO_PROFILE 42
//#define PG_FAILSAFE_CHANNEL_CONFIG 43
//#define PG_CHANNEL_RANGE_CONFIG 44
#define PG_RX_FAILSAFE_CHANNEL_CONFIG 43
#define PG_RX_CHANNEL_RANGE_CONFIG 44
//#define PG_MODE_COLOR_CONFIG 45
//#define PG_SPECIAL_COLOR_CONFIG 46

View file

@ -456,38 +456,6 @@ void createDefaultConfig(master_t *config)
resetTelemetryConfig(&config->telemetryConfig);
#endif
#ifdef SERIALRX_PROVIDER
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else
config->rxConfig.serialrx_provider = 0;
#endif
config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
config->rxConfig.spektrum_sat_bind = 0;
config->rxConfig.midrc = 1500;
config->rxConfig.mincheck = 1100;
config->rxConfig.maxcheck = 1900;
config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
if (i < NON_AUX_CHANNEL_COUNT) {
channelFailsafeConfiguration->mode = (i == THROTTLE) ? RX_FAILSAFE_MODE_HOLD : RX_FAILSAFE_MODE_AUTO;
}
else {
channelFailsafeConfiguration->mode = RX_FAILSAFE_MODE_HOLD;
}
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
}
config->rxConfig.rssi_channel = 0;
config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
config->rxConfig.rssi_ppm_invert = 0;
config->rxConfig.rcSmoothing = 1;
resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
config->pwmRxConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
config->armingConfig.disarm_kill_switch = 1;
@ -536,9 +504,9 @@ void createDefaultConfig(master_t *config)
// Radio
#ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", &config->rxConfig);
parseRcChannels("TAER1234");
#else
parseRcChannels("AETR1234", &config->rxConfig);
parseRcChannels("AETR1234");
#endif
resetRcControlsConfig(&config->rcControlsConfig);
@ -618,7 +586,7 @@ void createDefaultConfig(master_t *config)
config->controlRateProfiles[0].rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
config->controlRateProfiles[0].rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
config->controlRateProfiles[0].rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT;
parseRcChannels("TAER1234", &config->rxConfig);
parseRcChannels("TAER1234");
// { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
config->customMotorMixer[0].throttle = 1.0f;
@ -690,10 +658,11 @@ void createDefaultConfig(master_t *config)
void resetConfigs(void)
{
createDefaultConfig(&masterConfig);
pgResetAll(MAX_PROFILE_COUNT);
pgActivateProfile(0);
createDefaultConfig(&masterConfig);
setProfile(masterConfig.current_profile_index);
setControlRateProfile(masterConfig.current_profile_index);
#ifdef LED_STRIP
@ -723,9 +692,9 @@ static void activateConfig(void)
setAccelerationCalibrationValues();
setAccelerationFilter();
mixerUseConfigs(&masterConfig.flight3DConfig, &masterConfig.motorConfig, &masterConfig.mixerConfig, &masterConfig.rxConfig);
mixerUseConfigs(&masterConfig.flight3DConfig, &masterConfig.motorConfig, &masterConfig.mixerConfig);
#ifdef USE_SERVOS
servosUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoConf, &masterConfig.gimbalConfig, &masterConfig.rxConfig);
servosUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoConf, &masterConfig.gimbalConfig);
#endif
imuConfigure(&masterConfig.imuConfig, &currentProfile->pidProfile);
@ -736,7 +705,7 @@ static void activateConfig(void)
navigationUseConfig(&masterConfig.navConfig);
navigationUsePIDs(&currentProfile->pidProfile);
navigationUseRcControlsConfig(&masterConfig.rcControlsConfig);
navigationUseRxConfig(&masterConfig.rxConfig);
navigationUseRxConfig(rxConfig());
navigationUseFlight3DConfig(&masterConfig.flight3DConfig);
navigationUsemotorConfig(&masterConfig.motorConfig);
#endif
@ -920,8 +889,6 @@ void validateAndFixConfig(void)
featureClear(FEATURE_PWM_SERVO_DRIVER);
#endif
useRxConfig(&masterConfig.rxConfig);
serialConfig_t *serialConfig = &masterConfig.serialConfig;
if (!isSerialConfigValid(serialConfig)) {

View file

@ -214,7 +214,7 @@ void init(void)
// Spektrum satellite binding if enabled on startup.
// Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup.
// The rest of Spektrum initialization will happen later - via spektrumInit()
spektrumBind(&masterConfig.rxConfig);
spektrumBind(rxConfig());
break;
}
}
@ -482,7 +482,7 @@ void init(void)
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
dashboardInit(&masterConfig.rxConfig);
dashboardInit();
}
#endif
@ -525,9 +525,9 @@ void init(void)
cliInit(&masterConfig.serialConfig);
#endif
failsafeInit(&masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
failsafeInit(flight3DConfig()->deadband3d_throttle);
rxInit(&masterConfig.rxConfig, masterConfig.modeActivationConditions);
rxInit(masterConfig.modeActivationConditions);
#ifdef GPS
if (feature(FEATURE_GPS)) {
@ -545,7 +545,7 @@ void init(void)
&masterConfig.navConfig,
&currentProfile->pidProfile,
&masterConfig.rcControlsConfig,
&masterConfig.rxConfig,
rxConfig(),
&masterConfig.flight3DConfig,
&masterConfig.motorConfig
);

View file

@ -602,7 +602,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
}
break;
#ifdef USE_SERVOS
case MSP_SERVO:
sbufWriteData(dst, &servo, MAX_SUPPORTED_SERVOS * 2);
@ -912,8 +911,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
case MSP_RXFAIL_CONFIG:
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
sbufWriteU8(dst, rxConfig()->failsafe_channel_configurations[i].mode);
sbufWriteU16(dst, RXFAIL_STEP_TO_CHANNEL_VALUE(rxConfig()->failsafe_channel_configurations[i].step));
sbufWriteU8(dst, rxFailsafeChannelConfigs(i)->mode);
sbufWriteU16(dst, RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(i)->step));
}
break;
@ -1268,11 +1267,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
return MSP_RESULT_ERROR;
} else {
uint16_t frame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
for (int i = 0; i < channelCount; i++) {
frame[i] = sbufReadU16(src);
}
rxMspFrameReceive(frame, channelCount);
}
}
@ -1788,8 +1785,8 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_RXFAIL_CONFIG:
i = sbufReadU8(src);
if (i < MAX_SUPPORTED_RC_CHANNEL_COUNT) {
rxConfig()->failsafe_channel_configurations[i].mode = sbufReadU8(src);
rxConfig()->failsafe_channel_configurations[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
rxFailsafeChannelConfigs(i)->mode = sbufReadU8(src);
rxFailsafeChannelConfigs(i)->step = CHANNEL_VALUE_TO_RXFAIL_STEP(sbufReadU16(src));
} else {
return MSP_RESULT_ERROR;
}
@ -1831,7 +1828,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
if (dataSize % portConfigSize != 0) {
return MSP_RESULT_ERROR;
break;
}
uint8_t remainingPortsInPacket = dataSize / portConfigSize;
@ -1842,7 +1838,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier);
if (!portConfig) {
return MSP_RESULT_ERROR;
break;
}
portConfig->identifier = identifier;
@ -1870,7 +1865,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
i = sbufReadU8(src);
if (i >= LED_MAX_STRIP_LENGTH || dataSize != (1 + 4)) {
return MSP_RESULT_ERROR;
break;
}
ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[i];
*ledConfig = sbufReadU32(src);

View file

@ -119,7 +119,7 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
ibatLastServiced = currentTimeUs;
updateCurrentMeter(ibatTimeSinceLastServiced, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
updateCurrentMeter(ibatTimeSinceLastServiced, flight3DConfig()->deadband3d_throttle);
}
}
}
@ -204,7 +204,7 @@ void taskTelemetry(timeUs_t currentTimeUs)
telemetryCheckState();
if (!cliMode && feature(FEATURE_TELEMETRY)) {
telemetryProcess(currentTimeUs, &masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
telemetryProcess(currentTimeUs, flight3DConfig()->deadband3d_throttle);
}
}
#endif

View file

@ -313,7 +313,7 @@ void processRx(timeUs_t currentTimeUs)
failsafeUpdateState();
}
throttleStatus_e throttleStatus = calculateThrottleStatus(&masterConfig.rxConfig, flight3DConfig()->deadband3d_throttle);
const throttleStatus_e throttleStatus = calculateThrottleStatus(flight3DConfig()->deadband3d_throttle);
// When armed and motors aren't spinning, do beeps and then disarm
// board after delay so users without buzzer won't lose fingers.
@ -359,13 +359,13 @@ void processRx(timeUs_t currentTimeUs)
}
}
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, armingConfig()->disarm_kill_switch, armingConfig()->fixed_wing_auto_arm);
processRcStickPositions(throttleStatus, armingConfig()->disarm_kill_switch, armingConfig()->fixed_wing_auto_arm);
updateActivatedModes(masterConfig.modeActivationConditions, masterConfig.modeActivationOperator);
if (!cliMode) {
updateAdjustmentStates(masterConfig.adjustmentRanges);
processRcAdjustments(currentControlRateProfile, &masterConfig.rxConfig);
processRcAdjustments(currentControlRateProfile);
}
bool canUseHorizonMode = true;
@ -471,7 +471,7 @@ void processRx(timeUs_t currentTimeUs)
else {
if (throttleStatus == THROTTLE_LOW) {
if (IS_RC_MODE_ACTIVE(BOXAIRMODE) && !failsafeIsActive() && ARMING_FLAG(ARMED)) {
rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(&masterConfig.rxConfig);
rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus();
// ANTI_WINDUP at centred stick with MOTOR_STOP is needed on MRs and not needed on FWs
if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING))) {
@ -530,7 +530,7 @@ void filterRc(bool isRXDataNew)
}
const uint16_t filteredCycleTime = biquadFilterApply(&filteredCycleTimeState, (float) cycleTime);
rcInterpolationFactor = rxRefreshRate() / filteredCycleTime + 1;
rcInterpolationFactor = rxGetRefreshRate() / filteredCycleTime + 1;
if (isRXDataNew) {
for (int channel=0; channel < 4; channel++) {
@ -664,7 +664,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
updatePIDCoefficients(&currentProfile->pidProfile, currentControlRateProfile, &masterConfig.motorConfig);
// Calculate stabilisation
pidController(&currentProfile->pidProfile, currentControlRateProfile, &masterConfig.rxConfig);
pidController(&currentProfile->pidProfile, currentControlRateProfile, rxConfig());
#ifdef HIL
if (hilActive) {

View file

@ -120,26 +120,26 @@ bool areSticksInApModePosition(uint16_t ap_mode)
return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode;
}
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
throttleStatus_e calculateThrottleStatus(uint16_t deadband3d_throttle)
{
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig->midrc + deadband3d_throttle)))
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig()->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig()->midrc + deadband3d_throttle)))
return THROTTLE_LOW;
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig->mincheck))
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->mincheck))
return THROTTLE_LOW;
return THROTTLE_HIGH;
}
rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig)
rollPitchStatus_e calculateRollPitchCenterStatus(void)
{
if (((rcData[PITCH] < (rxConfig->midrc + AIRMODE_DEADBAND)) && (rcData[PITCH] > (rxConfig->midrc -AIRMODE_DEADBAND)))
&& ((rcData[ROLL] < (rxConfig->midrc + AIRMODE_DEADBAND)) && (rcData[ROLL] > (rxConfig->midrc -AIRMODE_DEADBAND))))
if (((rcData[PITCH] < (rxConfig()->midrc + AIRMODE_DEADBAND)) && (rcData[PITCH] > (rxConfig()->midrc -AIRMODE_DEADBAND)))
&& ((rcData[ROLL] < (rxConfig()->midrc + AIRMODE_DEADBAND)) && (rcData[ROLL] > (rxConfig()->midrc -AIRMODE_DEADBAND))))
return CENTERED;
return NOT_CENTERED;
}
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm)
void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm)
{
static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
static uint8_t rcSticks; // this hold sticks position for command combos
@ -151,9 +151,9 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
// checking sticks positions
for (i = 0; i < 4; i++) {
stTmp >>= 2;
if (rcData[i] > rxConfig->mincheck)
if (rcData[i] > rxConfig()->mincheck)
stTmp |= 0x80; // check for MIN
if (rcData[i] < rxConfig->maxcheck)
if (rcData[i] < rxConfig()->maxcheck)
stTmp |= 0x40; // check for MAX
}
if (stTmp == rcSticks) {
@ -640,7 +640,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
#define RESET_FREQUENCY_2HZ (1000 / 2)
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig)
void processRcAdjustments(controlRateConfig_t *controlRateConfig)
{
uint8_t adjustmentIndex;
uint32_t now = millis();
@ -675,9 +675,9 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx
if (adjustmentState->config->mode == ADJUSTMENT_MODE_STEP) {
int delta;
if (rcData[channelIndex] > rxConfig->midrc + 200) {
if (rcData[channelIndex] > rxConfig()->midrc + 200) {
delta = adjustmentState->config->data.stepConfig.step;
} else if (rcData[channelIndex] < rxConfig->midrc - 200) {
} else if (rcData[channelIndex] < rxConfig()->midrc - 200) {
delta = 0 - adjustmentState->config->data.stepConfig.step;
} else {
// returning the switch to the middle immediately resets the ready state

View file

@ -17,8 +17,6 @@
#pragma once
#include "rx/rx.h"
typedef enum {
BOXARM = 0,
BOXANGLE,
@ -173,9 +171,9 @@ typedef struct armingConfig_s {
bool areUsingSticksToArm(void);
bool areSticksInApModePosition(uint16_t ap_mode);
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig);
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm);
throttleStatus_e calculateThrottleStatus(uint16_t deadband3d_throttle);
rollPitchStatus_e calculateRollPitchCenterStatus(void);
void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm);
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions, modeActivationOperator_e modeActivationOperator);
@ -262,7 +260,7 @@ typedef struct adjustmentState_s {
void resetAdjustmentStates(void);
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig);
void processRcAdjustments(controlRateConfig_t *controlRateConfig);
bool isUsingSticksForArming(void);
bool isUsingNavigationModes(void);

View file

@ -55,8 +55,6 @@ static failsafeState_t failsafeState;
static failsafeConfig_t *failsafeConfig;
static rxConfig_t *rxConfig;
static uint16_t deadband3dThrottle; // default throttle deadband from MIDRC
static void failsafeReset(void)
@ -87,10 +85,8 @@ void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse)
failsafeReset();
}
void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle)
void failsafeInit(uint16_t deadband3d_throttle)
{
rxConfig = intialRxConfig;
deadband3dThrottle = deadband3d_throttle;
failsafeState.events = 0;
failsafeState.monitoring = false;
@ -143,7 +139,7 @@ static void failsafeActivate(void)
static void failsafeApplyControlInput(void)
{
for (int i = 0; i < 3; i++) {
rcData[i] = rxConfig->midrc;
rcData[i] = rxConfig()->midrc;
}
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
}
@ -205,7 +201,7 @@ void failsafeUpdateState(void)
case FAILSAFE_IDLE:
if (armed) {
// Track throttle command below minimum time
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig, deadband3dThrottle)) {
if (THROTTLE_HIGH == calculateThrottleStatus(deadband3dThrottle)) {
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
}
// Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming)

View file

@ -84,8 +84,7 @@ typedef struct failsafeState_s {
failsafeRxLinkState_e rxLinkState;
} failsafeState_t;
struct rxConfig_s;
void failsafeInit(struct rxConfig_s *intialRxConfig, uint16_t deadband3d_throttle);
void failsafeInit(uint16_t deadband3d_throttle);
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);
failsafeConfig_t * getActiveFailsafeConfig(void);

View file

@ -67,7 +67,6 @@ bool motorLimitReached = false;
mixerConfig_t *mixerConfig;
static flight3DConfig_t *flight3DConfig;
static motorConfig_t *motorConfig;
static rxConfig_t *rxConfig;
mixerMode_e currentMixerMode;
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
@ -265,13 +264,11 @@ static motorMixer_t *customMixers;
void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse,
motorConfig_t *motorConfigToUse,
mixerConfig_t *mixerConfigToUse,
rxConfig_t *rxConfigToUse)
mixerConfig_t *mixerConfigToUse)
{
flight3DConfig = flight3DConfigToUse;
motorConfig = motorConfigToUse;
mixerConfig = mixerConfigToUse;
rxConfig = rxConfigToUse;
}
bool isMixerEnabled(mixerMode_e mixerMode)
@ -432,17 +429,17 @@ void mixTable(void)
// Find min and max throttle based on condition.
if (feature(FEATURE_3D)) {
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
if ((rcCommand[THROTTLE] <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
throttleMax = flight3DConfig->deadband3d_low;
throttleMin = motorConfig->minthrottle;
throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if (rcCommand[THROTTLE] >= (rxConfig->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
throttleMax = motorConfig->maxthrottle;
throttleMin = flight3DConfig->deadband3d_high;
throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if ((throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
throttleCommand = throttleMax = flight3DConfig->deadband3d_low;
throttleMin = motorConfig->minthrottle;
} else { // Deadband handling from positive to negative
@ -486,7 +483,7 @@ void mixTable(void)
if (isFailsafeActive) {
motor[i] = constrain(motor[i], motorConfig->mincommand, motorConfig->maxthrottle);
} else if (feature(FEATURE_3D)) {
if (throttlePrevious <= (rxConfig->midrc - flight3DConfig->deadband3d_throttle)) {
if (throttlePrevious <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle)) {
motor[i] = constrain(motor[i], motorConfig->minthrottle, flight3DConfig->deadband3d_low);
} else {
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, motorConfig->maxthrottle);
@ -497,7 +494,7 @@ void mixTable(void)
// Motor stop handling
if (feature(FEATURE_MOTOR_STOP) && ARMING_FLAG(ARMED) && !feature(FEATURE_3D) && !isFailsafeActive) {
if (((rcData[THROTTLE]) < rxConfig->mincheck) || STATE(NAV_MOTOR_STOP_OR_IDLE)) {
if (((rcData[THROTTLE]) < rxConfig()->mincheck) || STATE(NAV_MOTOR_STOP_OR_IDLE)) {
motor[i] = motorConfig->mincommand;
}
}

View file

@ -107,13 +107,10 @@ extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
extern bool motorLimitReached;
struct motorConfig_s;
struct rxConfig_s;
void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse,
struct motorConfig_s *motorConfigToUse,
mixerConfig_t *mixerConfigToUse,
struct rxConfig_s *rxConfigToUse);
mixerConfig_t *mixerConfigToUse);
void writeAllMotors(int16_t mc);
void mixerLoadMix(int index, motorMixer_t *customMixers);

View file

@ -28,6 +28,8 @@
#include "flight/failsafe.h"
#include "flight/mixer.h"
#include "rx/rx.h"
/* GPS Home location data */
extern gpsLocation_t GPS_home;
extern uint16_t GPS_distanceToHome; // distance to home point in meters

View file

@ -148,7 +148,7 @@ bool adjustMulticopterAltitudeFromRCInput(void)
void setupMulticopterAltitudeController(void)
{
const throttleStatus_e throttleStatus = calculateThrottleStatus(posControl.rxConfig, posControl.flight3DConfig->deadband3d_throttle);
const throttleStatus_e throttleStatus = calculateThrottleStatus(posControl.flight3DConfig->deadband3d_throttle);
if (posControl.navConfig->general.flags.use_thr_mid_for_althold) {
altHoldThrottleRCZero = rcLookupThrottleMid();

View file

@ -22,6 +22,7 @@
#if defined(NAV)
#include "fc/runtime_config.h"
#include "rx/rx.h"
#define MIN_POSITION_UPDATE_RATE_HZ 5 // Minimum position update rate at which XYZ controllers would be applied
#define NAV_THROTTLE_CUTOFF_FREQENCY_HZ 4 // low-pass filter on throttle output
@ -245,6 +246,7 @@ typedef struct {
navigationFSMState_t onEvent[NAV_FSM_EVENT_COUNT];
} navigationFSMStateDescriptor_t;
typedef struct {
/* Flags and navigation system state */
navigationFSMState_t navState;

View file

@ -63,8 +63,6 @@ extern mixerMode_e currentMixerMode;
extern const mixer_t mixers[];
extern mixerConfig_t *mixerConfig;
static rxConfig_t *rxConfig;
servoMixerConfig_t *servoMixerConfig;
static uint8_t servoRuleCount = 0;
@ -134,12 +132,11 @@ const mixerRules_t servoMixers[] = {
static servoMixer_t *customServoMixers;
void servosUseConfigs(servoMixerConfig_t *servoMixerConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse, rxConfig_t *rxConfigToUse)
void servosUseConfigs(servoMixerConfig_t *servoMixerConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse)
{
servoMixerConfig = servoMixerConfigToUse;
servoConf = servoParamsToUse;
gimbalConfig = gimbalConfigToUse;
rxConfig = rxConfigToUse;
}
int16_t getFlaperonDirection(uint8_t servoPin) {
@ -346,7 +343,7 @@ void servoMixer(uint16_t flaperon_throw_offset, uint8_t flaperon_throw_inverted)
input[INPUT_STABILIZED_YAW] = axisPID[YAW];
// Reverse yaw servo when inverted in 3D mode
if (feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig->midrc)) {
if (feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->midrc)) {
input[INPUT_STABILIZED_YAW] *= -1;
}
}
@ -362,14 +359,14 @@ void servoMixer(uint16_t flaperon_throw_offset, uint8_t flaperon_throw_inverted)
// 2000 - 1500 = +500
// 1500 - 1500 = 0
// 1000 - 1500 = -500
input[INPUT_RC_ROLL] = rcData[ROLL] - rxConfig->midrc;
input[INPUT_RC_PITCH] = rcData[PITCH] - rxConfig->midrc;
input[INPUT_RC_YAW] = rcData[YAW] - rxConfig->midrc;
input[INPUT_RC_THROTTLE] = rcData[THROTTLE] - rxConfig->midrc;
input[INPUT_RC_AUX1] = rcData[AUX1] - rxConfig->midrc;
input[INPUT_RC_AUX2] = rcData[AUX2] - rxConfig->midrc;
input[INPUT_RC_AUX3] = rcData[AUX3] - rxConfig->midrc;
input[INPUT_RC_AUX4] = rcData[AUX4] - rxConfig->midrc;
input[INPUT_RC_ROLL] = rcData[ROLL] - rxConfig()->midrc;
input[INPUT_RC_PITCH] = rcData[PITCH] - rxConfig()->midrc;
input[INPUT_RC_YAW] = rcData[YAW] - rxConfig()->midrc;
input[INPUT_RC_THROTTLE] = rcData[THROTTLE] - rxConfig()->midrc;
input[INPUT_RC_AUX1] = rcData[AUX1] - rxConfig()->midrc;
input[INPUT_RC_AUX2] = rcData[AUX2] - rxConfig()->midrc;
input[INPUT_RC_AUX3] = rcData[AUX3] - rxConfig()->midrc;
input[INPUT_RC_AUX4] = rcData[AUX4] - rxConfig()->midrc;
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++)
servo[i] = 0;

View file

@ -125,5 +125,5 @@ void servoMixerLoadMix(int index, servoMixer_t *customServoMixers);
void loadCustomServoMixer(void);
int servoDirection(int servoIndex, int fromChannel);
struct gimbalConfig_s;
void servosUseConfigs(servoMixerConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, struct gimbalConfig_s *gimbalConfigToUse, struct rxConfig_s *rxConfigToUse);
void servosUseConfigs(servoMixerConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, struct gimbalConfig_s *gimbalConfigToUse);
void servosInit(servoMixer_t *customServoMixers);

View file

@ -60,8 +60,6 @@
#include "sensors/gyro.h"
#include "sensors/barometer.h"
#include "rx/rx.h"
#include "config/feature.h"
@ -75,7 +73,6 @@ controlRateConfig_t *getControlRateConfig(uint8_t profileIndex);
static timeUs_t nextDisplayUpdateAt = 0;
static bool displayPresent = false;
static const rxConfig_t *rxConfig;
static displayPort_t *displayPort;
#define PAGE_TITLE_LINE_COUNT 1
@ -476,10 +473,8 @@ void dashboardSetPage(pageId_e newPageId)
forcePageChange = true;
}
void dashboardInit(const rxConfig_t *rxConfigToUse)
void dashboardInit(void)
{
rxConfig = rxConfigToUse;
delay(200);
resetDisplay();
delay(200);
@ -489,8 +484,6 @@ void dashboardInit(const rxConfig_t *rxConfigToUse)
cmsDisplayPortRegister(displayPort);
#endif
rxConfig = rxConfigToUse;
dashboardSetPage(PAGE_WELCOME);
const uint32_t now = micros();
dashboardSetNextPageChangeAt(now + 5 * MICROSECONDS_IN_A_SECOND);

View file

@ -21,8 +21,7 @@ typedef enum {
PAGE_STATUS
} pageId_e;
struct rxConfig_s;
void dashboardInit(const struct rxConfig_s *intialRxConfig);
void dashboardInit(void);
void dashboardUpdate(timeUs_t currentTimeUs);
void dashboardSetPage(pageId_e newPageId);

View file

@ -1,5 +1,6 @@
/*
* This file is part of Cleanflight.
switch(rxFailsafeChannelConfigs(channel)->mode) {
v * This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -536,6 +537,26 @@ static const clivalue_t valueTable[] = {
{ "pitot_scale", VAR_FLOAT | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_PITOTMETER_CONFIG, offsetof(pitotmeterConfig_t, pitot_scale) },
#endif
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1200, 1700 }, PG_RX_CONFIG, offsetof(rxConfig_t, midrc) },
{ "min_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, mincheck) },
{ "max_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, maxcheck) },
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_channel) },
{ "rssi_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_scale) },
{ "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_ppm_invert) },
{ "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, rcSmoothing) },
#ifdef SERIAL_RX
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
#endif
#ifdef USE_RX_SPI
{ "rx_spi_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_SPI }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_spi_protocol) },
{ "rx_spi_id", VAR_UINT32 | MASTER_VALUE, .config.minmax = { 0, 0 }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_spi_id) },
{ "rx_spi_rf_channel_count", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 8 }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_spi_rf_channel_count) },
#endif
#ifdef SPEKTRUM_BIND
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
#endif
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_min_usec) },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
};
#else
@ -556,13 +577,6 @@ const clivalue_t valueTable[] = {
{ "async_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.asyncMode, .config.lookup = { TABLE_ASYNC_MODE } },
#endif
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &rxConfig()->midrc, .config.minmax = { 1200, 1700 } },
{ "min_check", VAR_UINT16 | MASTER_VALUE, &rxConfig()->mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "max_check", VAR_UINT16 | MASTER_VALUE, &rxConfig()->maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "rssi_channel", VAR_INT8 | MASTER_VALUE, &rxConfig()->rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
{ "rssi_scale", VAR_UINT8 | MASTER_VALUE, &rxConfig()->rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
{ "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
{ "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->rcSmoothing, .config.lookup = { TABLE_OFF_ON } },
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &pwmRxConfig()->inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &motorConfig()->minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
@ -675,17 +689,6 @@ const clivalue_t valueTable[] = {
{ "nav_fw_launch_climb_angle", VAR_UINT8 | MASTER_VALUE, &navConfig()->fw.launch_climb_angle, .config.minmax = { 5, 45 } },
#endif
#ifdef SERIAL_RX
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
#endif
#ifdef USE_RX_SPI
{ "rx_spi_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->rx_spi_protocol, .config.lookup = { TABLE_RX_SPI } },
{ "rx_spi_id", VAR_UINT32 | MASTER_VALUE, &rxConfig()->rx_spi_id, .config.minmax = { 0, 0 } },
{ "rx_spi_rf_channel_count", VAR_UINT8 | MASTER_VALUE, &rxConfig()->rx_spi_rf_channel_count, .config.minmax = { 0, 8 } },
#endif
#ifdef SPEKTRUM_BIND
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &rxConfig()->spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
#endif
#ifdef TELEMETRY
{ "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &telemetryConfig()->telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
@ -769,8 +772,6 @@ const clivalue_t valueTable[] = {
{ "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &failsafeConfig()->failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &failsafeConfig()->failsafe_procedure, .config.lookup = { TABLE_FAILSAFE_PROCEDURE } },
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &rxConfig()->rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 }, },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 }, },
@ -1060,6 +1061,7 @@ static void dumpPgValues(uint16_t valueSection, uint8_t dumpMask, pgn_t pgn, voi
}
}
}
#endif
static gyroConfig_t gyroConfigCopy;
static accelerometerConfig_t accelerometerConfigCopy;
@ -1072,6 +1074,9 @@ static barometerConfig_t barometerConfigCopy;
#ifdef PITOT
static pitotmeterConfig_t pitotmeterConfigCopy;
#endif
static rxConfig_t rxConfigCopy;
static rxFailsafeChannelConfig_t rxFailsafeChannelConfigsCopy[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static rxChannelRangeConfig_t rxChannelRangeConfigsCopy[NON_AUX_CHANNEL_COUNT];
static void backupConfigs(void)
{
@ -1087,6 +1092,13 @@ static void backupConfigs(void)
#ifdef PITOT
pitotmeterConfigCopy = *pitotmeterConfig();
#endif
rxConfigCopy = *rxConfig();
for (int ii = 0; ii < MAX_SUPPORTED_RC_CHANNEL_COUNT; ++ii) {
rxFailsafeChannelConfigsCopy[ii] = *rxFailsafeChannelConfigs(ii);
}
for (int ii = 0; ii < NON_AUX_CHANNEL_COUNT; ++ii) {
rxChannelRangeConfigsCopy[ii] = *rxChannelRangeConfigs(ii);
}
}
static void restoreConfigs(void)
@ -1102,10 +1114,15 @@ static void restoreConfigs(void)
#ifdef PITOT
*pitotmeterConfig() = pitotmeterConfigCopy;
#endif
*rxConfig() = rxConfigCopy;
for (int ii = 0; ii < MAX_SUPPORTED_RC_CHANNEL_COUNT; ++ii) {
*rxFailsafeChannelConfigs(ii) = rxFailsafeChannelConfigsCopy[ii];
}
for (int ii = 0; ii < NON_AUX_CHANNEL_COUNT; ++ii) {
*rxChannelRangeConfigs(ii) = rxChannelRangeConfigsCopy[ii];
}
}
#endif
static void *getDefaultPointer(const void *valuePointer, const master_t *defaultConfig)
{
return ((uint8_t *)valuePointer) - (uint32_t)&masterConfig + (uint32_t)defaultConfig;
@ -1144,6 +1161,7 @@ static void dumpValues(uint16_t valueSection, uint8_t dumpMask, const master_t *
#ifdef PITOT
dumpPgValues(MASTER_VALUE, dumpMask, PG_PITOT_CONFIG, &pitotmeterConfigCopy, pitotmeterConfig());
#endif
dumpPgValues(MASTER_VALUE, dumpMask, PG_RX_CONFIG, &rxConfigCopy, rxConfig());
return;
}
#endif
@ -1270,40 +1288,40 @@ static bool isEmpty(const char *string)
return *string == '\0';
}
static void printRxFail(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfig_t *defaultRxConfig)
static void printRxFail(uint8_t dumpMask, const rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs, const rxFailsafeChannelConfig_t *defaultRxFailsafeChannelConfigs)
{
// print out rxConfig failsafe settings
for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
const rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig->failsafe_channel_configurations[channel];
const rxFailsafeChannelConfiguration_t *channelFailsafeConfigurationDefault;
const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxFailsafeChannelConfigs[channel];
const rxFailsafeChannelConfig_t *channelFailsafeConfigDefault;
bool equalsDefault = true;
if (defaultRxConfig) {
channelFailsafeConfigurationDefault = &defaultRxConfig->failsafe_channel_configurations[channel];
equalsDefault = channelFailsafeConfiguration->mode == channelFailsafeConfigurationDefault->mode
&& channelFailsafeConfiguration->step == channelFailsafeConfigurationDefault->step;
if (defaultRxFailsafeChannelConfigs) {
channelFailsafeConfigDefault = &defaultRxFailsafeChannelConfigs[channel];
equalsDefault = channelFailsafeConfig->mode == channelFailsafeConfigDefault->mode
&& channelFailsafeConfig->step == channelFailsafeConfigDefault->step;
}
const bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
const bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
if (requireValue) {
const char *format = "rxfail %u %c %d\r\n";
cliDefaultPrintf(dumpMask, equalsDefault, format,
channel,
rxFailsafeModeCharacters[channelFailsafeConfigurationDefault->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigurationDefault->step)
rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigDefault->step)
);
cliDumpPrintf(dumpMask, equalsDefault, format,
channel,
rxFailsafeModeCharacters[channelFailsafeConfiguration->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
rxFailsafeModeCharacters[channelFailsafeConfig->mode],
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
);
} else {
const char *format = "rxfail %u %c\r\n";
cliDefaultPrintf(dumpMask, equalsDefault, format,
channel,
rxFailsafeModeCharacters[channelFailsafeConfigurationDefault->mode]
rxFailsafeModeCharacters[channelFailsafeConfigDefault->mode]
);
cliDumpPrintf(dumpMask, equalsDefault, format,
channel,
rxFailsafeModeCharacters[channelFailsafeConfiguration->mode]
rxFailsafeModeCharacters[channelFailsafeConfig->mode]
);
}
}
@ -1324,12 +1342,12 @@ static void cliRxFail(char *cmdline)
channel = atoi(ptr++);
if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig()->failsafe_channel_configurations[channel];
rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigs(channel);
uint16_t value;
rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
ptr = nextArg(ptr);
if (ptr) {
@ -1360,16 +1378,15 @@ static void cliRxFail(char *cmdline)
return;
}
channelFailsafeConfiguration->step = value;
channelFailsafeConfig->step = value;
} else if (requireValue) {
cliShowParseError();
return;
}
channelFailsafeConfiguration->mode = mode;
channelFailsafeConfig->mode = mode;
}
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfig->mode];
// triple use of cliPrintf below
// 1. acknowledge interpretation on command,
@ -1380,7 +1397,7 @@ static void cliRxFail(char *cmdline)
cliPrintf("rxfail %u %c %d\r\n",
channel,
modeCharacter,
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
);
} else {
cliPrintf("rxfail %u %c\r\n",
@ -1848,26 +1865,24 @@ static void cliMotorMix(char *cmdline)
#endif
}
static void printRxRange(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfig_t *defaultRxConfig)
static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channelRangeConfigs, const rxChannelRangeConfig_t *defaultChannelRangeConfigs)
{
const char *format = "rxrange %u %u %u\r\n";
for (uint32_t i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
const rxChannelRangeConfiguration_t *channelRangeConfiguration = &rxConfig->channelRanges[i];
bool equalsDefault = true;
if (defaultRxConfig) {
const rxChannelRangeConfiguration_t *channelRangeConfigurationDefault = &defaultRxConfig->channelRanges[i];
equalsDefault = channelRangeConfiguration->min == channelRangeConfigurationDefault->min
&& channelRangeConfiguration->max == channelRangeConfigurationDefault->max;
if (defaultChannelRangeConfigs) {
equalsDefault = channelRangeConfigs[i].min == defaultChannelRangeConfigs[i].min
&& channelRangeConfigs[i].max == defaultChannelRangeConfigs[i].max;
cliDefaultPrintf(dumpMask, equalsDefault, format,
i,
channelRangeConfigurationDefault->min,
channelRangeConfigurationDefault->max
defaultChannelRangeConfigs[i].min,
defaultChannelRangeConfigs[i].max
);
}
cliDumpPrintf(dumpMask, equalsDefault, format,
i,
channelRangeConfiguration->min,
channelRangeConfiguration->max
channelRangeConfigs[i].min,
channelRangeConfigs[i].max
);
}
}
@ -1878,9 +1893,9 @@ static void cliRxRange(char *cmdline)
char *ptr;
if (isEmpty(cmdline)) {
printRxRange(DUMP_MASTER, rxConfig(), NULL);
printRxRange(DUMP_MASTER, rxChannelRangeConfigs(0), NULL);
} else if (strcasecmp(cmdline, "reset") == 0) {
resetAllRxChannelRangeConfigurations(rxConfig()->channelRanges);
resetAllRxChannelRangeConfigurations();
} else {
ptr = cmdline;
i = atoi(ptr);
@ -1904,9 +1919,9 @@ static void cliRxRange(char *cmdline)
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
cliShowParseError();
} else {
rxChannelRangeConfiguration_t *channelRangeConfiguration = &rxConfig()->channelRanges[i];
channelRangeConfiguration->min = rangeMin;
channelRangeConfiguration->max = rangeMax;
rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigs(i);
channelRangeConfig->min = rangeMin;
channelRangeConfig->max = rangeMax;
}
} else {
cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
@ -2710,7 +2725,7 @@ static void cliMap(char *cmdline)
cliShowParseError();
return;
}
parseRcChannels(cmdline, &masterConfig.rxConfig);
parseRcChannels(cmdline);
}
cliPrint("Map: ");
uint32_t i;
@ -3258,8 +3273,8 @@ static void printConfig(char *cmdline, bool doDiff)
static master_t defaultConfig;
createDefaultConfig(&defaultConfig);
#ifdef USE_PARAMETER_GROUPS
backupConfigs();
#ifdef USE_PARAMETER_GROUPS
// reset all configs to defaults to do differencing
resetConfigs();
#if defined(TARGET_CONFIG)
@ -3317,7 +3332,7 @@ static void printConfig(char *cmdline, bool doDiff)
#endif
cliPrintHashLine("map");
printMap(dumpMask, rxConfig(), &defaultConfig.rxConfig);
printMap(dumpMask, &rxConfigCopy, rxConfig());
cliPrintHashLine("serial");
printSerial(dumpMask, serialConfig(), &defaultConfig.serialConfig);
@ -3340,10 +3355,10 @@ static void printConfig(char *cmdline, bool doDiff)
printAdjustmentRange(dumpMask, masterConfig.adjustmentRanges, defaultConfig.adjustmentRanges);
cliPrintHashLine("rxrange");
printRxRange(dumpMask, rxConfig(), &defaultConfig.rxConfig);
printRxRange(dumpMask, rxChannelRangeConfigsCopy, rxChannelRangeConfigs(0));
cliPrintHashLine("rxfail");
printRxFail(dumpMask, rxConfig(), &defaultConfig.rxConfig);
printRxFail(dumpMask, rxFailsafeChannelConfigsCopy, rxFailsafeChannelConfigs(0));
cliPrintHashLine("master");
dumpValues(MASTER_VALUE, dumpMask, &defaultConfig);
@ -3379,10 +3394,8 @@ static void printConfig(char *cmdline, bool doDiff)
if (dumpMask & DUMP_RATES) {
cliDumpRateProfile(getCurrentControlRateProfile(), dumpMask, &defaultConfig);
}
#ifdef USE_PARAMETER_GROUPS
// restore configs from copies
restoreConfigs();
#endif
}
static void cliDump(char *cmdline)

View file

@ -17,6 +17,8 @@
#pragma once
#include "rx/rx.h"
uint8_t rxMspFrameStatus(void);
void rxMspFrameReceive(uint16_t *frame, int channelCount);
void rxMspInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);

View file

@ -30,6 +30,9 @@
#include "common/utils.h"
#include "config/feature.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/adc.h"
#include "drivers/pwm_rx.h"
@ -89,9 +92,67 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
#define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
rxRuntimeConfig_t rxRuntimeConfig;
static const rxConfig_t *rxConfig;
static uint8_t rcSampleIndex = 0;
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
#ifndef SERIALRX_PROVIDER
#define SERIALRX_PROVIDER 0
#endif
PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
.serialrx_provider = SERIALRX_PROVIDER,
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
.spektrum_sat_bind = 0,
.midrc = 1500,
.mincheck = 1100,
.maxcheck = 1900,
.rx_min_usec = 885, // any of first 4 channels below this value will trigger rx loss detection
.rx_max_usec = 2115, // any of first 4 channels above this value will trigger rx loss detection
.rssi_channel = 0,
.rssi_scale = RSSI_SCALE_DEFAULT,
.rssi_ppm_invert = 0,
.rcSmoothing = 1
);
void resetAllRxChannelRangeConfigurations(void)
{
// set default calibration to full range and 1:1 mapping
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
rxChannelRangeConfigs(i)->min = PWM_RANGE_MIN;
rxChannelRangeConfigs(i)->max = PWM_RANGE_MAX;
}
}
PG_REGISTER_ARR_WITH_RESET_FN(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs, PG_RX_CHANNEL_RANGE_CONFIG, 0);
void pgResetFn_rxChannelRangeConfigs(rxChannelRangeConfig_t *rxChannelRangeConfigs)
{
// set default calibration to full range and 1:1 mapping
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
rxChannelRangeConfigs[i].min = PWM_RANGE_MIN;
rxChannelRangeConfigs[i].max = PWM_RANGE_MAX;
}
}
PG_REGISTER_ARR_WITH_RESET_FN(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs, PG_RX_FAILSAFE_CHANNEL_CONFIG, 0);
void pgResetFn_rxFailsafeChannelConfigs(rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs)
{
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
if (i== THROTTLE) {
rxFailsafeChannelConfigs[i].mode = RX_FAILSAFE_MODE_HOLD;
rxFailsafeChannelConfigs[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->rx_min_usec);
} else {
rxFailsafeChannelConfigs[i].mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
rxFailsafeChannelConfigs[i].step = CHANNEL_VALUE_TO_RXFAIL_STEP(rxConfig()->midrc);
}
}
}
static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
{
UNUSED(rxRuntimeConfig);
@ -105,13 +166,6 @@ static uint8_t nullFrameStatus(void)
return RX_FRAME_PENDING;
}
void serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
void useRxConfig(const rxConfig_t *rxConfigToUse)
{
rxConfig = rxConfigToUse;
}
#define REQUIRED_CHANNEL_MASK 0x0F // first 4 channels
static uint8_t validFlightChannelMask;
@ -127,8 +181,8 @@ STATIC_UNIT_TESTED bool rxHaveValidFlightChannels(void)
STATIC_UNIT_TESTED bool isPulseValid(uint16_t pulseDuration)
{
return pulseDuration >= rxConfig->rx_min_usec &&
pulseDuration <= rxConfig->rx_max_usec;
return pulseDuration >= rxConfig()->rx_min_usec &&
pulseDuration <= rxConfig()->rx_max_usec;
}
// pulse duration is in micro seconds (usec)
@ -140,86 +194,13 @@ STATIC_UNIT_TESTED void rxUpdateFlightChannelStatus(uint8_t channel, bool valid)
}
}
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration) {
// set default calibration to full range and 1:1 mapping
for (int i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
rxChannelRangeConfiguration->min = PWM_RANGE_MIN;
rxChannelRangeConfiguration->max = PWM_RANGE_MAX;
rxChannelRangeConfiguration++;
}
}
void rxInit(const rxConfig_t *rxConfig, const modeActivationCondition_t *modeActivationConditions)
{
uint8_t i;
uint16_t value;
useRxConfig(rxConfig);
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rcSampleIndex = 0;
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rcData[i] = rxConfig->midrc;
rcInvalidPulsPeriod[i] = millis() + MAX_INVALID_PULS_TIME;
}
rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig->midrc : rxConfig->rx_min_usec;
// Initialize ARM switch to OFF position when arming via switch is defined
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
const modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[i];
if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) {
// ARM switch is defined, determine an OFF value
if (modeActivationCondition->range.startStep > 0) {
value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.startStep - 1));
} else {
value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.endStep + 1));
}
// Initialize ARM AUX channel to OFF value
rcData[modeActivationCondition->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = value;
}
}
#ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) {
serialRxInit(rxConfig, &rxRuntimeConfig);
}
#endif
#ifndef SKIP_RX_MSP
if (feature(FEATURE_RX_MSP)) {
rxMspInit(rxConfig, &rxRuntimeConfig);
}
#endif
#ifdef USE_RX_SPI
if (feature(FEATURE_RX_SPI)) {
const bool enabled = rxSpiInit(rxConfig, &rxRuntimeConfig);
if (!enabled) {
featureClear(FEATURE_RX_SPI);
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
}
}
#endif
#ifndef SKIP_RX_PWM_PPM
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
rxRuntimeConfig.rxRefreshRate = 20000;
rxPwmInit(rxConfig, &rxRuntimeConfig);
}
#endif
}
#ifdef SERIAL_RX
void serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
bool enabled = false;
switch (rxConfig->serialrx_provider) {
#ifdef USE_SERIALRX_SPEKTRUM
case SERIALRX_SPEKTRUM1024:
enabled = spektrumInit(rxConfig, rxRuntimeConfig);
break;
case SERIALRX_SPEKTRUM2048:
enabled = spektrumInit(rxConfig, rxRuntimeConfig);
break;
@ -259,11 +240,7 @@ void serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
enabled = false;
break;
}
if (!enabled) {
featureClear(FEATURE_RX_SERIAL);
rxRuntimeConfig->rcReadRawFn = nullReadRawRC;
}
return enabled;
}
static uint8_t serialRxFrameStatus(const rxConfig_t *rxConfig)
@ -315,6 +292,70 @@ static uint8_t serialRxFrameStatus(const rxConfig_t *rxConfig)
}
#endif
void rxInit(const modeActivationCondition_t *modeActivationConditions)
{
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rcSampleIndex = 0;
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rcData[i] = rxConfig()->midrc;
rcInvalidPulsPeriod[i] = millis() + MAX_INVALID_PULS_TIME;
}
rcData[THROTTLE] = (feature(FEATURE_3D)) ? rxConfig()->midrc : rxConfig()->rx_min_usec;
// Initialize ARM switch to OFF position when arming via switch is defined
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
const modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[i];
if (modeActivationCondition->modeId == BOXARM && IS_RANGE_USABLE(&modeActivationCondition->range)) {
// ARM switch is defined, determine an OFF value
uint16_t value;
if (modeActivationCondition->range.startStep > 0) {
value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.startStep - 1));
} else {
value = MODE_STEP_TO_CHANNEL_VALUE((modeActivationCondition->range.endStep + 1));
}
// Initialize ARM AUX channel to OFF value
rcData[modeActivationCondition->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = value;
}
}
#ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) {
const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig);
if (!enabled) {
featureClear(FEATURE_RX_SERIAL);
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
}
}
#endif
#ifndef SKIP_RX_MSP
if (feature(FEATURE_RX_MSP)) {
rxMspInit(rxConfig(), &rxRuntimeConfig);
}
#endif
#ifdef USE_RX_SPI
if (feature(FEATURE_RX_SPI)) {
const bool enabled = rxSpiInit(rxConfig(), &rxRuntimeConfig);
if (!enabled) {
featureClear(FEATURE_RX_SPI);
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
}
}
#endif
#ifndef SKIP_RX_PWM_PPM
if (feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM)) {
rxRuntimeConfig.rxRefreshRate = 20000;
rxPwmInit(rxConfig(), &rxRuntimeConfig);
}
#endif
}
static uint8_t calculateChannelRemapping(const uint8_t *channelMap, uint8_t channelMapEntryCount, uint8_t channelToRemap)
{
if (channelToRemap < channelMapEntryCount) {
@ -332,7 +373,8 @@ bool rxAreFlightChannelsValid(void)
{
return rxFlightChannelsValid;
}
static bool isRxDataDriven(void) {
static bool isRxDataDriven(void)
{
return !(feature(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM));
}
@ -373,7 +415,7 @@ bool updateRx(timeUs_t currentTimeUs)
#ifdef SERIAL_RX
if (feature(FEATURE_RX_SERIAL)) {
const uint8_t frameStatus = serialRxFrameStatus(rxConfig);
const uint8_t frameStatus = serialRxFrameStatus(rxConfig());
if (frameStatus & RX_FRAME_COMPLETE) {
rxDataReceived = true;
rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0;
@ -434,7 +476,7 @@ static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
static int16_t rcDataMean[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT];
static bool rxSamplesCollected = false;
uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
const uint8_t currentSampleIndex = rcSampleIndex % PPM_AND_PWM_SAMPLE_COUNT;
// update the recent samples and compute the average of them
rcSamples[chan][currentSampleIndex] = sample;
@ -448,32 +490,26 @@ static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
}
rcDataMean[chan] = 0;
uint8_t sampleIndex;
for (sampleIndex = 0; sampleIndex < PPM_AND_PWM_SAMPLE_COUNT; sampleIndex++)
for (int sampleIndex = 0; sampleIndex < PPM_AND_PWM_SAMPLE_COUNT; sampleIndex++) {
rcDataMean[chan] += rcSamples[chan][sampleIndex];
}
return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT;
}
static uint16_t getRxfailValue(uint8_t channel)
{
const rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig->failsafe_channel_configurations[channel];
uint8_t mode = channelFailsafeConfiguration->mode;
switch(mode) {
switch(rxFailsafeChannelConfigs(channel)->mode) {
case RX_FAILSAFE_MODE_AUTO:
switch (channel) {
case ROLL:
case PITCH:
case YAW:
return rxConfig->midrc;
return rxConfig()->midrc;
case THROTTLE:
if (feature(FEATURE_3D))
return rxConfig->midrc;
return rxConfig()->midrc;
else
return rxConfig->rx_min_usec;
return rxConfig()->rx_min_usec;
}
/* no break */
@ -483,18 +519,18 @@ static uint16_t getRxfailValue(uint8_t channel)
return rcData[channel];
case RX_FAILSAFE_MODE_SET:
return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step);
return RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(channel)->step);
}
}
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range)
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfig_t *range)
{
// Avoid corruption of channel with a value of PPM_RCVR_TIMEOUT
if (sample == PPM_RCVR_TIMEOUT) {
return PPM_RCVR_TIMEOUT;
}
sample = scaleRange(sample, range.min, range.max, PWM_RANGE_MIN, PWM_RANGE_MAX);
sample = scaleRange(sample, range->min, range->max, PWM_RANGE_MIN, PWM_RANGE_MAX);
sample = MIN(MAX(PWM_PULSE_MIN, sample), PWM_PULSE_MAX);
return sample;
@ -504,14 +540,14 @@ static void readRxChannelsApplyRanges(void)
{
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
const uint8_t rawChannel = calculateChannelRemapping(rxConfig->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);
const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);
// sample the channel
uint16_t sample = (*rxRuntimeConfig.rcReadRawFn)(&rxRuntimeConfig, rawChannel);
// apply the rx calibration
if (channel < NON_AUX_CHANNEL_COUNT) {
sample = applyRxChannelRangeConfiguraton(sample, rxConfig->channelRanges[channel]);
sample = applyRxChannelRangeConfiguraton(sample, rxChannelRangeConfigs(channel));
}
rcRaw[channel] = sample;
@ -520,8 +556,6 @@ static void readRxChannelsApplyRanges(void)
static void detectAndApplySignalLossBehaviour(void)
{
int channel;
uint16_t sample;
bool useValueFromRx = true;
bool rxIsDataDriven = isRxDataDriven();
uint32_t currentMilliTime = millis();
@ -543,9 +577,9 @@ static void detectAndApplySignalLossBehaviour(void)
rxResetFlightChannelStatus();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
sample = (useValueFromRx) ? rcRaw[channel] : PPM_RCVR_TIMEOUT;
uint16_t sample = (useValueFromRx) ? rcRaw[channel] : PPM_RCVR_TIMEOUT;
bool validPulse = isPulseValid(sample);
@ -575,7 +609,7 @@ static void detectAndApplySignalLossBehaviour(void)
rxIsInFailsafeMode = rxIsInFailsafeModeNotDataDriven = true;
failsafeOnValidDataFailed();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
rcData[channel] = getRxfailValue(channel);
}
}
@ -603,25 +637,25 @@ void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
rcSampleIndex++;
}
void parseRcChannels(const char *input, rxConfig_t *rxConfig)
void parseRcChannels(const char *input)
{
const char *c, *s;
for (c = input; *c; c++) {
s = strchr(rcChannelLetters, *c);
if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS))
rxConfig->rcmap[s - rcChannelLetters] = c - input;
rxConfig()->rcmap[s - rcChannelLetters] = c - input;
}
}
void updateRSSIPWM(void)
static void updateRSSIPWM(void)
{
int16_t pwmRssi = 0;
// Read value of AUX channel as rssi
pwmRssi = rcData[rxConfig->rssi_channel - 1];
pwmRssi = rcData[rxConfig()->rssi_channel - 1];
// RSSI_Invert option
if (rxConfig->rssi_ppm_invert) {
if (rxConfig()->rssi_ppm_invert) {
pwmRssi = ((2000 - pwmRssi) + 1000);
}
@ -632,7 +666,7 @@ void updateRSSIPWM(void)
#define RSSI_ADC_SAMPLE_COUNT 16
//#define RSSI_SCALE (0xFFF / 100.0f)
void updateRSSIADC(timeUs_t currentTimeUs)
static void updateRSSIADC(timeUs_t currentTimeUs)
{
#ifndef USE_ADC
UNUSED(currentTimeUs);
@ -646,17 +680,15 @@ void updateRSSIADC(timeUs_t currentTimeUs)
}
rssiUpdateAtUs = currentTimeUs + DELAY_50_HZ;
int16_t adcRssiMean = 0;
uint16_t adcRssiSample = adcGetChannel(ADC_RSSI);
uint8_t rssiPercentage = adcRssiSample / rxConfig->rssi_scale;
const uint16_t adcRssiSample = adcGetChannel(ADC_RSSI);
const uint8_t rssiPercentage = adcRssiSample / rxConfig()->rssi_scale;
adcRssiSampleIndex = (adcRssiSampleIndex + 1) % RSSI_ADC_SAMPLE_COUNT;
adcRssiSamples[adcRssiSampleIndex] = rssiPercentage;
uint8_t sampleIndex;
for (sampleIndex = 0; sampleIndex < RSSI_ADC_SAMPLE_COUNT; sampleIndex++) {
int16_t adcRssiMean = 0;
for (int sampleIndex = 0; sampleIndex < RSSI_ADC_SAMPLE_COUNT; sampleIndex++) {
adcRssiMean += adcRssiSamples[sampleIndex];
}
@ -669,14 +701,14 @@ void updateRSSIADC(timeUs_t currentTimeUs)
void updateRSSI(timeUs_t currentTimeUs)
{
if (rxConfig->rssi_channel > 0) {
if (rxConfig()->rssi_channel > 0) {
updateRSSIPWM();
} else if (feature(FEATURE_RSSI_ADC)) {
updateRSSIADC(currentTimeUs);
}
}
uint16_t rxRefreshRate(void)
uint16_t rxGetRefreshRate(void)
{
return rxRuntimeConfig.rxRefreshRate;
}

View file

@ -17,7 +17,11 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "common/time.h"
#include "config/parameter_group.h"
#define STICK_CHANNEL_COUNT 4
@ -58,17 +62,13 @@ typedef enum {
SERIALRX_PROVIDER_MAX = SERIALRX_JETIEXBUS
} SerialRXType;
#define SERIALRX_PROVIDER_COUNT (SERIALRX_PROVIDER_MAX + 1)
#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 12
#define MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT 8
#define MAX_SUPPORTED_RC_CHANNEL_COUNT (18)
#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18
#define NON_AUX_CHANNEL_COUNT 4
#define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT)
#if MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT > MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT
#define MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT
#else
@ -89,27 +89,29 @@ typedef enum {
RX_FAILSAFE_MODE_AUTO = 0,
RX_FAILSAFE_MODE_HOLD,
RX_FAILSAFE_MODE_SET,
RX_FAILSAFE_MODE_INVALID,
RX_FAILSAFE_MODE_INVALID
} rxFailsafeChannelMode_e;
#define RX_FAILSAFE_MODE_COUNT 3
typedef enum {
RX_FAILSAFE_TYPE_FLIGHT = 0,
RX_FAILSAFE_TYPE_AUX,
RX_FAILSAFE_TYPE_AUX
} rxFailsafeChannelType_e;
#define RX_FAILSAFE_TYPE_COUNT 2
typedef struct rxFailsafeChannelConfiguration_s {
typedef struct rxFailsafeChannelConfig_s {
uint8_t mode; // See rxFailsafeChannelMode_e
uint8_t step;
} rxFailsafeChannelConfiguration_t;
} rxFailsafeChannelConfig_t;
PG_DECLARE_ARR(rxFailsafeChannelConfig_t, MAX_SUPPORTED_RC_CHANNEL_COUNT, rxFailsafeChannelConfigs);
typedef struct rxChannelRangeConfiguration_s {
typedef struct rxChannelRangeConfig_s {
uint16_t min;
uint16_t max;
} rxChannelRangeConfiguration_t;
} rxChannelRangeConfig_t;
PG_DECLARE_ARR(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
typedef struct rxConfig_s {
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
@ -130,11 +132,10 @@ typedef struct rxConfig_s {
uint16_t rx_min_usec;
uint16_t rx_max_usec;
rxFailsafeChannelConfiguration_t failsafe_channel_configurations[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxChannelRangeConfiguration_t channelRanges[NON_AUX_CHANNEL_COUNT];
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
struct rxRuntimeConfig_s;
@ -151,19 +152,18 @@ typedef struct rxRuntimeConfig_s {
extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
struct modeActivationCondition_s;
void rxInit(const rxConfig_t *rxConfig, const struct modeActivationCondition_s *modeActivationConditions);
void useRxConfig(const rxConfig_t *rxConfigToUse);
void rxInit(const struct modeActivationCondition_s *modeActivationConditions);
bool updateRx(timeUs_t currentTimeUs);
bool rxIsReceivingSignal(void);
bool rxAreFlightChannelsValid(void);
void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs);
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
void parseRcChannels(const char *input);
void updateRSSI(timeUs_t currentTimeUs);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration);
void resetAllRxChannelRangeConfigurations(void);
void suspendRxSignal(void);
void resumeRxSignal(void);
uint16_t rxRefreshRate(void);
uint16_t rxGetRefreshRate(void);

View file

@ -177,7 +177,7 @@ int32_t currentSensorToCentiamps(uint16_t src)
return (millivolts * 1000) / (int32_t)batteryConfig->currentMeterScale; // current in 0.01A steps
}
void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
{
static int32_t amperageRaw = 0;
static int64_t mAhdrawnRaw = 0;
@ -193,7 +193,7 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea
case CURRENT_SENSOR_VIRTUAL:
amperage = (int32_t)batteryConfig->currentMeterOffset;
if (ARMING_FLAG(ARMED)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(rxConfig, deadband3d_throttle);
throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle);
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
throttleOffset = 0;
throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);

View file

@ -71,8 +71,7 @@ const char * getBatteryStateString(void);
void updateBattery(uint32_t vbatTimeDelta);
void batteryInit(batteryConfig_t *initialBatteryConfig);
struct rxConfig_s;
void updateCurrentMeter(int32_t lastUpdateAt, struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
void updateCurrentMeter(int32_t lastUpdateAt, uint16_t deadband3d_throttle);
int32_t currentMeterToCentiamps(uint16_t src);
uint8_t calculateBatteryPercentage(void);

View file

@ -75,7 +75,7 @@
void targetConfiguration(struct master_s *config)
{
config->mixerConfig.mixerMode = MIXER_HEX6X;
config->rxConfig.serialrx_provider = 2;
rxConfig()->serialrx_provider = 2;
featureSet(FEATURE_RX_SERIAL);
config->serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
}

View file

@ -76,14 +76,14 @@ void targetConfiguration(struct master_s *config)
{
gyroConfig()->looptime = 1000;
config->rxConfig.rcmap[0] = 1;
config->rxConfig.rcmap[1] = 2;
config->rxConfig.rcmap[2] = 3;
config->rxConfig.rcmap[3] = 0;
config->rxConfig.rcmap[4] = 4;
config->rxConfig.rcmap[5] = 5;
config->rxConfig.rcmap[6] = 6;
config->rxConfig.rcmap[7] = 7;
rxConfig()->rcmap[0] = 1;
rxConfig()->rcmap[1] = 2;
rxConfig()->rcmap[2] = 3;
rxConfig()->rcmap[3] = 0;
rxConfig()->rcmap[4] = 4;
rxConfig()->rcmap[5] = 5;
rxConfig()->rcmap[6] = 6;
rxConfig()->rcmap[7] = 7;
featureSet(FEATURE_VBAT);
featureSet(FEATURE_LED_STRIP);

View file

@ -46,8 +46,6 @@
#include "io/gps.h"
#include "rx/rx.h"
#include "fc/config.h"
#include "flight/mixer.h"
@ -192,12 +190,12 @@ static void sendGpsAltitude(void)
}
#endif
static void sendThrottleOrBatterySizeAsRpm(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
static void sendThrottleOrBatterySizeAsRpm(uint16_t deadband3d_throttle)
{
uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER;
sendDataHead(ID_RPM);
if (ARMING_FLAG(ARMED)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(rxConfig, deadband3d_throttle);
const throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle);
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
throttleForRPM = 0;
serialize16(throttleForRPM);
@ -493,7 +491,7 @@ void checkFrSkyTelemetryState(void)
freeFrSkyTelemetryPort();
}
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
void handleFrSkyTelemetry(uint16_t deadband3d_throttle)
{
if (!frskyTelemetryEnabled) {
return;
@ -524,7 +522,7 @@ void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
if ((cycleNum % 8) == 0) { // Sent every 1s
sendTemperature1();
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
sendThrottleOrBatterySizeAsRpm(deadband3d_throttle);
if (feature(FEATURE_VBAT)) {
sendVoltage();

View file

@ -17,14 +17,12 @@
#pragma once
#include "rx/rx.h"
typedef enum {
FRSKY_VFAS_PRECISION_LOW = 0,
FRSKY_VFAS_PRECISION_HIGH
} frskyVFasPrecision_e;
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
void handleFrSkyTelemetry(uint16_t deadband3d_throttle);
void checkFrSkyTelemetryState(void);
void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig);

View file

@ -137,10 +137,10 @@ void telemetryCheckState(void)
}
void telemetryProcess(timeUs_t currentTimeUs, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
void telemetryProcess(timeUs_t currentTimeUs, uint16_t deadband3d_throttle)
{
#if defined(TELEMETRY_FRSKY)
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
handleFrSkyTelemetry(deadband3d_throttle);
#else
UNUSED(rxConfig);
UNUSED(deadband3d_throttle);

View file

@ -54,8 +54,7 @@ bool telemetryCheckRxPortShared(const serialPortConfig_t *portConfig);
extern serialPort_t *telemetrySharedPort;
void telemetryCheckState(void);
struct rxConfig_s;
void telemetryProcess(timeUs_t currentTimeUs, struct rxConfig_s *rxConfig, uint16_t deadband3d_throttle);
void telemetryProcess(timeUs_t currentTimeUs, uint16_t deadband3d_throttle);
bool telemetryDetermineEnabledState(portSharing_e portSharing);