mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Better configuration range for luxfloat in configurator
This commit is contained in:
parent
b4ea0bea19
commit
087e3ae0f4
1 changed files with 4 additions and 4 deletions
|
@ -878,9 +878,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
headSerialReply(3 * PID_ITEM_COUNT);
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) { // 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, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 40.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.D_f[i] * 1000.0f), 0, 255));
|
||||
serialize8(constrain(lrintf(currentProfile->pidProfile.D_f[i] * 4000.0f), 0, 255));
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
|
@ -1334,9 +1334,9 @@ static bool processInCommand(void)
|
|||
case MSP_SET_PID:
|
||||
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
|
||||
for (i = 0; i < 3; i++) {
|
||||
currentProfile->pidProfile.P_f[i] = (float)read8() / 10.0f;
|
||||
currentProfile->pidProfile.P_f[i] = (float)read8() / 40.0f;
|
||||
currentProfile->pidProfile.I_f[i] = (float)read8() / 100.0f;
|
||||
currentProfile->pidProfile.D_f[i] = (float)read8() / 1000.0f;
|
||||
currentProfile->pidProfile.D_f[i] = (float)read8() / 4000.0f;
|
||||
}
|
||||
for (i = 3; i < PID_ITEM_COUNT; i++) {
|
||||
if (i == PIDLEVEL) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue