1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Allow inflight adjustments for floating-point based PID controllers.

This commit is contained in:
Dominic Clifton 2015-01-30 20:54:34 +01:00
parent e33fd411c5
commit f77a762b48
12 changed files with 295 additions and 34 deletions

View file

@ -865,7 +865,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_PID:
headSerialReply(3 * PID_ITEM_COUNT);
if (currentProfile->pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
if (currentProfile->pidProfile.pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
for (i = 0; i < 3; i++) {
serialize8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 10.0f), 0, 250));
serialize8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 250));
@ -896,7 +896,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_PID_CONTROLLER:
headSerialReply(1);
serialize8(currentProfile->pidController);
serialize8(currentProfile->pidProfile.pidController);
break;
case MSP_MODE_RANGES:
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
@ -1205,11 +1205,11 @@ static bool processInCommand(void)
currentProfile->accelerometerTrims.values.roll = read16();
break;
case MSP_SET_PID_CONTROLLER:
currentProfile->pidController = read8();
setPIDController(currentProfile->pidController);
currentProfile->pidProfile.pidController = read8();
setPIDController(currentProfile->pidProfile.pidController);
break;
case MSP_SET_PID:
if (currentProfile->pidController == 2) {
if (currentProfile->pidProfile.pidController == 2) {
for (i = 0; i < 3; i++) {
currentProfile->pidProfile.P_f[i] = (float)read8() / 10.0f;
currentProfile->pidProfile.I_f[i] = (float)read8() / 100.0f;