Merge pull request #1984 from betaflight/3.1_msp
Add 3.1 MSP parameters
This commit is contained in:
commit
e51e49647e
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define EEPROM_CONF_VERSION 147
|
||||
#define EEPROM_CONF_VERSION 148
|
||||
|
||||
void initEEPROM(void);
|
||||
void writeEEPROM();
|
||||
|
|
|
@ -177,13 +177,13 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->dterm_notch_cutoff = 160;
|
||||
pidProfile->vbatPidCompensation = 0;
|
||||
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
|
||||
pidProfile->levelAngleLimit = 70.0f; // 70 degrees
|
||||
pidProfile->levelAngleLimit = 70; // 70 degrees
|
||||
pidProfile->levelSensitivity = 100; // 100 degrees at full stick
|
||||
pidProfile->setpointRelaxRatio = 30;
|
||||
pidProfile->dtermSetpointWeight = 200;
|
||||
pidProfile->yawRateAccelLimit = 20.0f;
|
||||
pidProfile->rateAccelLimit = 0.0f;
|
||||
pidProfile->itermThrottleThreshold = 350;
|
||||
pidProfile->levelSensitivity = 100.0f;
|
||||
}
|
||||
|
||||
void resetProfile(profile_t *profile)
|
||||
|
|
|
@ -1139,6 +1139,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, motorConfig()->useUnsyncedPwm);
|
||||
sbufWriteU8(dst, motorConfig()->motorPwmProtocol);
|
||||
sbufWriteU16(dst, motorConfig()->motorPwmRate);
|
||||
sbufWriteU16(dst, (uint16_t)(motorConfig()->digitalIdleOffsetPercent * 100));
|
||||
break;
|
||||
|
||||
case MSP_FILTER_CONFIG :
|
||||
|
@ -1166,6 +1167,8 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, 0); // reserved
|
||||
sbufWriteU16(dst, currentProfile->pidProfile.rateAccelLimit * 10);
|
||||
sbufWriteU16(dst, currentProfile->pidProfile.yawRateAccelLimit * 10);
|
||||
sbufWriteU8(dst, currentProfile->pidProfile.levelAngleLimit);
|
||||
sbufWriteU8(dst, currentProfile->pidProfile.levelSensitivity);
|
||||
break;
|
||||
|
||||
case MSP_SENSOR_CONFIG:
|
||||
|
@ -1461,7 +1464,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
case MSP_SET_RESET_CURR_PID:
|
||||
resetProfile(currentProfile);
|
||||
break;
|
||||
|
||||
case MSP_SET_SENSOR_ALIGNMENT:
|
||||
gyroConfig()->gyro_align = sbufReadU8(src);
|
||||
accelerometerConfig()->acc_align = sbufReadU8(src);
|
||||
|
@ -1478,6 +1480,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
motorConfig()->motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_BRUSHED);
|
||||
#endif
|
||||
motorConfig()->motorPwmRate = sbufReadU16(src);
|
||||
if (dataSize > 7) {
|
||||
motorConfig()->digitalIdleOffsetPercent = sbufReadU16(src) / 100.0f;
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_FILTER_CONFIG:
|
||||
|
@ -1514,6 +1519,10 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // reserved
|
||||
currentProfile->pidProfile.rateAccelLimit = sbufReadU16(src) / 10.0f;
|
||||
currentProfile->pidProfile.yawRateAccelLimit = sbufReadU16(src) / 10.0f;
|
||||
if (dataSize > 17) {
|
||||
currentProfile->pidProfile.levelAngleLimit = sbufReadU8(src);
|
||||
currentProfile->pidProfile.levelSensitivity = sbufReadU8(src);
|
||||
}
|
||||
pidInitConfig(¤tProfile->pidProfile);
|
||||
break;
|
||||
|
||||
|
|
|
@ -72,7 +72,8 @@ typedef struct pidProfile_s {
|
|||
uint8_t dterm_average_count; // Configurable delta count for dterm
|
||||
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
|
||||
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
|
||||
float levelAngleLimit;
|
||||
uint8_t levelAngleLimit; // Max angle in degrees in level mode
|
||||
uint8_t levelSensitivity; // Angle mode sensitivity reflected in degrees assuming user using full stick
|
||||
|
||||
// Betaflight PID controller parameters
|
||||
uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
|
||||
|
@ -80,7 +81,6 @@ typedef struct pidProfile_s {
|
|||
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
|
||||
float yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
|
||||
float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
|
||||
float levelSensitivity;
|
||||
} pidProfile_t;
|
||||
|
||||
typedef struct pidConfig_s {
|
||||
|
|
|
@ -715,8 +715,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
|
||||
{ "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
|
||||
|
||||
{ "level_stick_sensitivity", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelSensitivity, .config.minmax = { 10.0f, 200.0f } },
|
||||
{ "level_angle_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelAngleLimit, .config.minmax = { 10.0f, 120.0f } },
|
||||
{ "level_stick_sensitivity", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelSensitivity, .config.minmax = { 10, 200 } },
|
||||
{ "level_angle_limit", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.levelAngleLimit, .config.minmax = { 10, 120 } },
|
||||
|
||||
#ifdef BLACKBOX
|
||||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &blackboxConfig()->rate_num, .config.minmax = { 1, 32 } },
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
#define MSP_PROTOCOL_VERSION 0
|
||||
|
||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||
#define API_VERSION_MINOR 23 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
#define API_VERSION_MINOR 24 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||
|
||||
#define API_VERSION_LENGTH 2
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@ void targetConfiguration(master_t *config)
|
|||
config->profile[profileId].pidProfile.I8[YAW] = 45;
|
||||
config->profile[profileId].pidProfile.P8[PIDLEVEL] = 30;
|
||||
config->profile[profileId].pidProfile.D8[PIDLEVEL] = 30;
|
||||
config->profile[profileId].pidProfile.levelSensitivity = 50.0f;
|
||||
config->profile[profileId].pidProfile.levelSensitivity = 50;
|
||||
|
||||
for (int rateProfileId = 0; rateProfileId < MAX_RATEPROFILES; rateProfileId++) {
|
||||
config->profile[profileId].controlRateProfile[rateProfileId].rcRate8 = 100;
|
||||
|
|
Loading…
Reference in New Issue