Merge pull request #10761 from ctzsnooze/rc-update-msp-and-whitespace-fixes
msp and other small fixes to bring 10727 up to date with 10723
This commit is contained in:
commit
12a4016ff0
|
@ -4957,7 +4957,7 @@ static void cliRcSmoothing(const char *cmdName, char *cmdline)
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
rcSmoothingFilter_t *rcSmoothingData = getRcSmoothingData();
|
rcSmoothingFilter_t *rcSmoothingData = getRcSmoothingData();
|
||||||
cliPrint("# RC Smoothing Type: ");
|
cliPrint("# RC Smoothing Type: ");
|
||||||
if (rxConfig()->rc_smoothing_mode == ON) {
|
if (rxConfig()->rc_smoothing_mode) {
|
||||||
cliPrintLine("FILTER");
|
cliPrintLine("FILTER");
|
||||||
if (rcSmoothingAutoCalculate()) {
|
if (rcSmoothingAutoCalculate()) {
|
||||||
const uint16_t avgRxFrameUs = rcSmoothingData->averageFrameTimeUs;
|
const uint16_t avgRxFrameUs = rcSmoothingData->averageFrameTimeUs;
|
||||||
|
@ -4969,22 +4969,22 @@ static void cliRcSmoothing(const char *cmdName, char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency);
|
cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency);
|
||||||
if (rcSmoothingData->setpointCutoffSetting == 0) {
|
if (rcSmoothingData->setpointCutoffSetting) {
|
||||||
cliPrintLine("(auto)");
|
|
||||||
} else {
|
|
||||||
cliPrintLine("(manual)");
|
cliPrintLine("(manual)");
|
||||||
}
|
|
||||||
cliPrintf("# Active FF cutoff: %dhz (", rcSmoothingData->feedforwardCutoffFrequency);
|
|
||||||
if (rcSmoothingData->ffCutoffSetting == 0) {
|
|
||||||
cliPrintLine("auto)");
|
|
||||||
} else {
|
} else {
|
||||||
cliPrintLine("manual)");
|
cliPrintLine("(auto)");
|
||||||
}
|
}
|
||||||
cliPrintf("# Active throttle cutoff: %dhz (", rcSmoothingData->throttleCutoffFrequency);
|
cliPrintf("# Active FF cutoff: %dhz ", rcSmoothingData->feedforwardCutoffFrequency);
|
||||||
if (rcSmoothingData->ffCutoffSetting == 0) {
|
if (rcSmoothingData->ffCutoffSetting) {
|
||||||
cliPrintLine("auto)");
|
cliPrintLine("(manual)");
|
||||||
} else {
|
} else {
|
||||||
cliPrintLine("manual)");
|
cliPrintLine("(auto)");
|
||||||
|
}
|
||||||
|
cliPrintf("# Active throttle cutoff: %dhz ", rcSmoothingData->throttleCutoffFrequency);
|
||||||
|
if (rcSmoothingData->ffCutoffSetting) {
|
||||||
|
cliPrintLine("(manual)");
|
||||||
|
} else {
|
||||||
|
cliPrintLine("(auto)");
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
cliPrintLine("OFF");
|
cliPrintLine("OFF");
|
||||||
|
|
|
@ -473,7 +473,7 @@ static const char * const lookupTableOffOnAuto[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
const char* const lookupTableFeedforwardAveraging[] = {
|
const char* const lookupTableFeedforwardAveraging[] = {
|
||||||
"NONE", "2_POINT", "3_POINT", "4_POINT"
|
"OFF", "2_POINT", "3_POINT", "4_POINT"
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char* const lookupTableDshotBitbangedTimer[] = {
|
static const char* const lookupTableDshotBitbangedTimer[] = {
|
||||||
|
|
|
@ -58,11 +58,6 @@ typedef enum {
|
||||||
CENTERED
|
CENTERED
|
||||||
} rollPitchStatus_e;
|
} rollPitchStatus_e;
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
OFF,
|
|
||||||
ON
|
|
||||||
} rcSmoothingMode_e;
|
|
||||||
|
|
||||||
#define ROL_LO (1 << (2 * ROLL))
|
#define ROL_LO (1 << (2 * ROLL))
|
||||||
#define ROL_CE (3 << (2 * ROLL))
|
#define ROL_CE (3 << (2 * ROLL))
|
||||||
#define ROL_HI (2 << (2 * ROLL))
|
#define ROL_HI (2 << (2 * ROLL))
|
||||||
|
|
|
@ -1487,8 +1487,8 @@ static bool mspProcessOutCommand(int16_t cmdMSP, sbuf_t *dst)
|
||||||
sbufWriteU8(dst, rxConfig()->spektrum_sat_bind);
|
sbufWriteU8(dst, rxConfig()->spektrum_sat_bind);
|
||||||
sbufWriteU16(dst, rxConfig()->rx_min_usec);
|
sbufWriteU16(dst, rxConfig()->rx_min_usec);
|
||||||
sbufWriteU16(dst, rxConfig()->rx_max_usec);
|
sbufWriteU16(dst, rxConfig()->rx_max_usec);
|
||||||
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcInterpolation)
|
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcInterpolation
|
||||||
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcInterpolationInterval)
|
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcInterpolationInterval
|
||||||
sbufWriteU16(dst, rxConfig()->airModeActivateThreshold * 10 + 1000);
|
sbufWriteU16(dst, rxConfig()->airModeActivateThreshold * 10 + 1000);
|
||||||
#ifdef USE_RX_SPI
|
#ifdef USE_RX_SPI
|
||||||
sbufWriteU8(dst, rxSpiConfig()->rx_spi_protocol);
|
sbufWriteU8(dst, rxSpiConfig()->rx_spi_protocol);
|
||||||
|
@ -1502,7 +1502,7 @@ static bool mspProcessOutCommand(int16_t cmdMSP, sbuf_t *dst)
|
||||||
sbufWriteU8(dst, rxConfig()->fpvCamAngleDegrees);
|
sbufWriteU8(dst, rxConfig()->fpvCamAngleDegrees);
|
||||||
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcSmoothingChannels
|
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rcSmoothingChannels
|
||||||
#if defined(USE_RC_SMOOTHING_FILTER)
|
#if defined(USE_RC_SMOOTHING_FILTER)
|
||||||
sbufWriteU8(dst, rxConfig()->rc_smoothing_mode);
|
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rc_smoothing_type
|
||||||
sbufWriteU8(dst, rxConfig()->rc_smoothing_setpoint_cutoff);
|
sbufWriteU8(dst, rxConfig()->rc_smoothing_setpoint_cutoff);
|
||||||
sbufWriteU8(dst, rxConfig()->rc_smoothing_feedforward_cutoff);
|
sbufWriteU8(dst, rxConfig()->rc_smoothing_feedforward_cutoff);
|
||||||
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rc_smoothing_input_type
|
sbufWriteU8(dst, 0); // not required in API 1.44, was rxConfig()->rc_smoothing_input_type
|
||||||
|
@ -1524,6 +1524,12 @@ static bool mspProcessOutCommand(int16_t cmdMSP, sbuf_t *dst)
|
||||||
sbufWriteU8(dst, rxConfig()->rc_smoothing_auto_factor_rpy);
|
sbufWriteU8(dst, rxConfig()->rc_smoothing_auto_factor_rpy);
|
||||||
#else
|
#else
|
||||||
sbufWriteU8(dst, 0);
|
sbufWriteU8(dst, 0);
|
||||||
|
#endif
|
||||||
|
// Added in MSP API 1.44
|
||||||
|
#if defined(USE_RC_SMOOTHING_FILTER)
|
||||||
|
sbufWriteU8(dst, rxConfig()->rc_smoothing_mode);
|
||||||
|
#else
|
||||||
|
sbufWriteU8(dst, 0);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
case MSP_FAILSAFE_CONFIG:
|
case MSP_FAILSAFE_CONFIG:
|
||||||
|
@ -3256,7 +3262,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
||||||
// Added in MSP API 1.40
|
// Added in MSP API 1.40
|
||||||
sbufReadU8(src); // not required in API 1.44, was rxConfigMutable()->rcSmoothingChannels
|
sbufReadU8(src); // not required in API 1.44, was rxConfigMutable()->rcSmoothingChannels
|
||||||
#if defined(USE_RC_SMOOTHING_FILTER)
|
#if defined(USE_RC_SMOOTHING_FILTER)
|
||||||
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_mode, sbufReadU8(src));
|
sbufReadU8(src); // not required in API 1.44, was rc_smoothing_type
|
||||||
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_setpoint_cutoff, sbufReadU8(src));
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_setpoint_cutoff, sbufReadU8(src));
|
||||||
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_feedforward_cutoff, sbufReadU8(src));
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_feedforward_cutoff, sbufReadU8(src));
|
||||||
sbufReadU8(src); // not required in API 1.44, was rc_smoothing_input_type
|
sbufReadU8(src); // not required in API 1.44, was rc_smoothing_input_type
|
||||||
|
@ -3290,7 +3296,14 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
|
||||||
sbufReadU8(src);
|
sbufReadU8(src);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
if (sbufBytesRemaining(src) >= 1) {
|
||||||
|
// Added in MSP API 1.44
|
||||||
|
#if defined(USE_RC_SMOOTHING_FILTER)
|
||||||
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_mode, sbufReadU8(src));
|
||||||
|
#else
|
||||||
|
sbufReadU8(src);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_SET_FAILSAFE_CONFIG:
|
case MSP_SET_FAILSAFE_CONFIG:
|
||||||
failsafeConfigMutable()->failsafe_delay = sbufReadU8(src);
|
failsafeConfigMutable()->failsafe_delay = sbufReadU8(src);
|
||||||
|
|
|
@ -59,7 +59,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
||||||
.fpvCamAngleDegrees = 0,
|
.fpvCamAngleDegrees = 0,
|
||||||
.airModeActivateThreshold = 25,
|
.airModeActivateThreshold = 25,
|
||||||
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT,
|
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT,
|
||||||
.rc_smoothing_mode = ON,
|
.rc_smoothing_mode = 1,
|
||||||
.rc_smoothing_setpoint_cutoff = 0,
|
.rc_smoothing_setpoint_cutoff = 0,
|
||||||
.rc_smoothing_feedforward_cutoff = 0,
|
.rc_smoothing_feedforward_cutoff = 0,
|
||||||
.rc_smoothing_throttle_cutoff = 0,
|
.rc_smoothing_throttle_cutoff = 0,
|
||||||
|
|
|
@ -29,42 +29,39 @@
|
||||||
|
|
||||||
typedef struct rxConfig_s {
|
typedef struct rxConfig_s {
|
||||||
uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
|
uint8_t rcmap[RX_MAPPABLE_CHANNEL_COUNT]; // mapping of radio channels to internal RPYTA+ order
|
||||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||||
uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
|
uint8_t serialrx_inverted; // invert the serial RX protocol compared to it's default setting
|
||||||
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
||||||
ioTag_t spektrum_bind_pin_override_ioTag;
|
ioTag_t spektrum_bind_pin_override_ioTag;
|
||||||
ioTag_t spektrum_bind_plug_ioTag;
|
ioTag_t spektrum_bind_plug_ioTag;
|
||||||
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||||
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
||||||
uint8_t rssi_channel;
|
uint8_t rssi_channel;
|
||||||
uint8_t rssi_scale;
|
uint8_t rssi_scale;
|
||||||
uint8_t rssi_invert;
|
uint8_t rssi_invert;
|
||||||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||||
uint16_t mincheck; // minimum rc end
|
uint16_t mincheck; // minimum rc end
|
||||||
uint16_t maxcheck; // maximum rc end
|
uint16_t maxcheck; // maximum rc end
|
||||||
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
|
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
|
||||||
uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
|
uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
|
||||||
|
|
||||||
uint16_t rx_min_usec;
|
uint16_t rx_min_usec;
|
||||||
uint16_t rx_max_usec;
|
uint16_t rx_max_usec;
|
||||||
uint8_t max_aux_channel;
|
uint8_t max_aux_channel;
|
||||||
uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
|
uint8_t rssi_src_frame_errors; // true to use frame drop flags in the rx protocol
|
||||||
int8_t rssi_offset; // offset applied to the RSSI value before it is returned
|
int8_t rssi_offset; // offset applied to the RSSI value before it is returned
|
||||||
uint8_t rc_smoothing_mode; // Whether filter based rc smoothing is on or off
|
uint8_t rc_smoothing_mode; // Whether filter based rc smoothing is on or off
|
||||||
uint8_t rc_smoothing_setpoint_cutoff; // Filter cutoff frequency for the setpoint filter (0 = auto)
|
uint8_t rc_smoothing_setpoint_cutoff; // Filter cutoff frequency for the setpoint filter (0 = auto)
|
||||||
uint8_t rc_smoothing_feedforward_cutoff; // Filter cutoff frequency for the feedforward filter (0 = auto)
|
uint8_t rc_smoothing_feedforward_cutoff; // Filter cutoff frequency for the feedforward filter (0 = auto)
|
||||||
uint8_t rc_smoothing_throttle_cutoff; // Filter cutoff frequency for the setpoint filter (0 = auto)
|
uint8_t rc_smoothing_throttle_cutoff; // Filter cutoff frequency for the setpoint filter (0 = auto)
|
||||||
uint8_t rc_smoothing_debug_axis; // Axis to log as debug values when debug_mode = RC_SMOOTHING
|
uint8_t rc_smoothing_debug_axis; // Axis to log as debug values when debug_mode = RC_SMOOTHING
|
||||||
uint8_t rc_smoothing_auto_factor_rpy; // Used to adjust the "smoothness" determined by the auto cutoff calculations
|
uint8_t rc_smoothing_auto_factor_rpy; // Used to adjust the "smoothness" determined by the auto cutoff calculations
|
||||||
uint8_t rc_smoothing_auto_factor_throttle; // Used to adjust the "smoothness" determined by the auto cutoff calculations
|
uint8_t rc_smoothing_auto_factor_throttle; // Used to adjust the "smoothness" determined by the auto cutoff calculations
|
||||||
uint8_t rssi_src_frame_lpf_period; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s)
|
uint8_t rssi_src_frame_lpf_period; // Period of the cutoff frequency for the source frame RSSI filter (in 0.1 s)
|
||||||
|
uint8_t srxl2_unit_id; // Spektrum SRXL2 RX unit id
|
||||||
uint8_t srxl2_unit_id; // Spektrum SRXL2 RX unit id
|
uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate
|
||||||
uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate
|
uint8_t sbus_baud_fast; // Select SBus fast baud rate
|
||||||
uint8_t sbus_baud_fast; // Select SBus fast baud rate
|
uint8_t crsf_use_rx_snr; // Use RX SNR (in dB) instead of RSSI dBm for CRSF
|
||||||
uint8_t crsf_use_rx_snr; // Use RX SNR (in dB) instead of RSSI dBm for CRSF
|
uint32_t msp_override_channels_mask; // Channels to override when the MSP override mode is enabled
|
||||||
|
|
||||||
uint32_t msp_override_channels_mask; // Channels to override when the MSP override mode is enabled
|
|
||||||
} rxConfig_t;
|
} rxConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(rxConfig_t, rxConfig);
|
PG_DECLARE(rxConfig_t, rxConfig);
|
||||||
|
|
|
@ -560,7 +560,6 @@ TEST(pidControllerTest, testFeedForward) {
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].F);
|
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].F);
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].F);
|
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].F);
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
|
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(pidControllerTest, testItermRelax) {
|
TEST(pidControllerTest, testItermRelax) {
|
||||||
|
|
Loading…
Reference in New Issue