mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 16:25:26 +03:00
Merge remote-tracking branch 'origin/master' into dzikuvx-drop-MSP_PID_ADVANCED
This commit is contained in:
commit
a9b9a5c736
5 changed files with 32 additions and 92 deletions
|
@ -140,18 +140,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
|||
// from mixer.c
|
||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
static const char pidnames[] =
|
||||
"ROLL;"
|
||||
"PITCH;"
|
||||
"YAW;"
|
||||
"ALT;"
|
||||
"Pos;"
|
||||
"PosR;"
|
||||
"NavR;"
|
||||
"LEVEL;"
|
||||
"MAG;"
|
||||
"VEL;";
|
||||
|
||||
typedef enum {
|
||||
MSP_SDCARD_STATE_NOT_PRESENT = 0,
|
||||
MSP_SDCARD_STATE_FATAL = 1,
|
||||
|
@ -708,12 +696,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
break;
|
||||
|
||||
case MSP_PIDNAMES:
|
||||
for (const char *c = pidnames; *c; c++) {
|
||||
sbufWriteU8(dst, *c);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_MODE_RANGES:
|
||||
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
const modeActivationCondition_t *mac = modeActivationConditions(i);
|
||||
|
@ -1218,24 +1200,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, 0);
|
||||
break;
|
||||
|
||||
case MSP_FILTER_CONFIG :
|
||||
sbufWriteU8(dst, gyroConfig()->gyro_main_lpf_hz);
|
||||
sbufWriteU16(dst, pidProfile()->dterm_lpf_hz);
|
||||
sbufWriteU16(dst, pidProfile()->yaw_lpf_hz);
|
||||
sbufWriteU16(dst, 0); //Was gyroConfig()->gyro_notch_hz
|
||||
sbufWriteU16(dst, 1); //Was gyroConfig()->gyro_notch_cutoff
|
||||
sbufWriteU16(dst, 0); //BF: pidProfile()->dterm_notch_hz
|
||||
sbufWriteU16(dst, 1); //pidProfile()->dterm_notch_cutoff
|
||||
|
||||
sbufWriteU16(dst, 0); //BF: masterConfig.gyro_soft_notch_hz_2
|
||||
sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2
|
||||
|
||||
sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz);
|
||||
sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff);
|
||||
|
||||
sbufWriteU16(dst, 0); //Was gyroConfig()->gyro_stage2_lowpass_hz
|
||||
break;
|
||||
|
||||
case MSP_INAV_PID:
|
||||
sbufWriteU8(dst, 0); //Legacy, no longer in use async processing value
|
||||
sbufWriteU16(dst, 0); //Legacy, no longer in use async processing value
|
||||
|
@ -2181,47 +2145,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_SET_FILTER_CONFIG :
|
||||
if (dataSize >= 5) {
|
||||
gyroConfigMutable()->gyro_main_lpf_hz = sbufReadU8(src);
|
||||
pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 500);
|
||||
pidProfileMutable()->yaw_lpf_hz = constrain(sbufReadU16(src), 0, 255);
|
||||
if (dataSize >= 9) {
|
||||
sbufReadU16(src); //Was gyroConfigMutable()->gyro_notch_hz
|
||||
sbufReadU16(src); //Was gyroConfigMutable()->gyro_notch_cutoff
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
if (dataSize >= 13) {
|
||||
sbufReadU16(src);
|
||||
sbufReadU16(src);
|
||||
pidInitFilters();
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
if (dataSize >= 17) {
|
||||
sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_hz_2
|
||||
sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_cutoff_2
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
||||
if (dataSize >= 21) {
|
||||
accelerometerConfigMutable()->acc_notch_hz = constrain(sbufReadU16(src), 0, 255);
|
||||
accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255);
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
||||
if (dataSize >= 22) {
|
||||
sbufReadU16(src); //Was gyro_stage2_lowpass_hz
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_SET_INAV_PID:
|
||||
if (dataSize == 15) {
|
||||
sbufReadU8(src); //Legacy, no longer in use async processing value
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue