Skip to content

Commit 5a4aaed

Browse files
authored
Merge pull request #6900 from iNavFlight/dzikuvx-smith-predictor
Smith Predictor on PID measurement
2 parents c098bde + b265369 commit 5a4aaed

File tree

9 files changed

+191
-2
lines changed

9 files changed

+191
-2
lines changed

docs/Settings.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -498,6 +498,9 @@
498498
| smartport_fuel_unit | MAH | | | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] |
499499
| smartport_master_halfduplex | ON | | | |
500500
| smartport_master_inverted | OFF | | | |
501+
| smith_predictor_delay | 0 | 0 | 8 | Expected delay of the gyro signal. In milliseconds |
502+
| smith_predictor_lpf_hz | 50 | 1 | 500 | Cutoff frequency for the Smith Predictor Low Pass Filter |
503+
| smith_predictor_strength | 0.5 | 0 | 1 | The strength factor of a Smith Predictor of PID measurement. In percents |
501504
| spektrum_sat_bind | `SPEKTRUM_SAT_BIND_DISABLED` | SPEKTRUM_SAT_BIND_DISABLED | SPEKTRUM_SAT_BIND_MAX | 0 = disabled. Used to bind the spektrum satellite to RX |
502505
| srxl2_baud_fast | ON | | | |
503506
| srxl2_unit_id | 1 | 0 | 15 | |

src/main/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -320,6 +320,8 @@ main_sources(COMMON_SRC
320320
flight/imu.h
321321
flight/kalman.c
322322
flight/kalman.h
323+
flight/smith_predictor.c
324+
flight/smith_predictor.h
323325
flight/mixer.c
324326
flight/mixer.h
325327
flight/pid.c

src/main/build/debug.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,5 +83,6 @@ typedef enum {
8383
DEBUG_FW_D,
8484
DEBUG_IMU2,
8585
DEBUG_ALTITUDE,
86+
DEBUG_SMITH_COMPENSATOR,
8687
DEBUG_COUNT
8788
} debugType_e;

src/main/fc/settings.yaml

Lines changed: 23 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,8 @@ tables:
9393
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
9494
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
9595
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
96-
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D", "IMU2", "ALTITUDE"]
96+
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D", "IMU2", "ALTITUDE",
97+
"SMITH_COMPENSATOR"]
9798
- name: async_mode
9899
values: ["NONE", "GYRO", "ALL"]
99100
- name: aux_operator
@@ -2061,6 +2062,27 @@ groups:
20612062
field: fixedWingLevelTrim
20622063
min: -10
20632064
max: 10
2065+
- name: smith_predictor_strength
2066+
description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2067+
default_value: 0.5
2068+
field: smithPredictorStrength
2069+
condition: USE_SMITH_PREDICTOR
2070+
min: 0
2071+
max: 1
2072+
- name: smith_predictor_delay
2073+
description: "Expected delay of the gyro signal. In milliseconds"
2074+
default_value: 0
2075+
field: smithPredictorDelay
2076+
condition: USE_SMITH_PREDICTOR
2077+
min: 0
2078+
max: 8
2079+
- name: smith_predictor_lpf_hz
2080+
description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2081+
default_value: 50
2082+
field: smithPredictorFilterHz
2083+
condition: USE_SMITH_PREDICTOR
2084+
min: 1
2085+
max: 500
20642086

20652087
- name: PG_PID_AUTOTUNE_CONFIG
20662088
type: pidAutotuneConfig_t

src/main/flight/pid.c

Lines changed: 41 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@ FILE_COMPILE_FOR_SPEED
4848
#include "flight/rpm_filter.h"
4949
#include "flight/secondary_imu.h"
5050
#include "flight/kalman.h"
51+
#include "flight/smith_predictor.h"
5152

5253
#include "io/gps.h"
5354

@@ -109,6 +110,8 @@ typedef struct {
109110
bool itermFreezeActive;
110111

111112
biquadFilter_t rateTargetFilter;
113+
114+
smithPredictor_t smithPredictor;
112115
} pidState_t;
113116

114117
STATIC_FASTRAM bool pidFiltersConfigured = false;
@@ -159,7 +162,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn;
159162
static EXTENDED_FASTRAM bool levelingEnabled = false;
160163
static EXTENDED_FASTRAM float fixedWingLevelTrim;
161164

162-
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 1);
165+
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 2);
163166

164167
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
165168
.bank_mc = {
@@ -297,6 +300,12 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
297300
#endif
298301

299302
.fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT,
303+
304+
#ifdef USE_SMITH_PREDICTOR
305+
.smithPredictorStrength = SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT,
306+
.smithPredictorDelay = SETTING_SMITH_PREDICTOR_DELAY_DEFAULT,
307+
.smithPredictorFilterHz = SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT,
308+
#endif
300309
);
301310

302311
bool pidInitFilters(void)
@@ -349,6 +358,30 @@ bool pidInitFilters(void)
349358
}
350359
}
351360

361+
#ifdef USE_SMITH_PREDICTOR
362+
smithPredictorInit(
363+
&pidState[FD_ROLL].smithPredictor,
364+
pidProfile()->smithPredictorDelay,
365+
pidProfile()->smithPredictorStrength,
366+
pidProfile()->smithPredictorFilterHz,
367+
getLooptime()
368+
);
369+
smithPredictorInit(
370+
&pidState[FD_PITCH].smithPredictor,
371+
pidProfile()->smithPredictorDelay,
372+
pidProfile()->smithPredictorStrength,
373+
pidProfile()->smithPredictorFilterHz,
374+
getLooptime()
375+
);
376+
smithPredictorInit(
377+
&pidState[FD_YAW].smithPredictor,
378+
pidProfile()->smithPredictorDelay,
379+
pidProfile()->smithPredictorStrength,
380+
pidProfile()->smithPredictorFilterHz,
381+
getLooptime()
382+
);
383+
#endif
384+
352385
pidFiltersConfigured = true;
353386

354387
return true;
@@ -1052,6 +1085,13 @@ void FAST_CODE pidController(float dT)
10521085
pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget);
10531086
}
10541087
#endif
1088+
1089+
#ifdef USE_SMITH_PREDICTOR
1090+
DEBUG_SET(DEBUG_SMITH_COMPENSATOR, axis, pidState[axis].gyroRate);
1091+
pidState[axis].gyroRate = applySmithPredictor(axis, &pidState[axis].smithPredictor, pidState[axis].gyroRate);
1092+
DEBUG_SET(DEBUG_SMITH_COMPENSATOR, axis + 3, pidState[axis].gyroRate);
1093+
#endif
1094+
10551095
DEBUG_SET(DEBUG_PID_MEASUREMENT, axis, pidState[axis].gyroRate);
10561096
}
10571097

src/main/flight/pid.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,11 @@ typedef struct pidProfile_s {
161161
#endif
162162

163163
float fixedWingLevelTrim;
164+
#ifdef USE_SMITH_PREDICTOR
165+
float smithPredictorStrength;
166+
float smithPredictorDelay;
167+
uint16_t smithPredictorFilterHz;
168+
#endif
164169
} pidProfile_t;
165170

166171
typedef struct pidAutotuneConfig_s {

src/main/flight/smith_predictor.c

Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
/*
2+
* This file is part of INAV Project.
3+
*
4+
* This Source Code Form is subject to the terms of the Mozilla Public
5+
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
6+
* You can obtain one at http://mozilla.org/MPL/2.0/.
7+
*
8+
* Alternatively, the contents of this file may be used under the terms
9+
* of the GNU General Public License Version 3, as described below:
10+
*
11+
* This file is free software: you may copy, redistribute and/or modify
12+
* it under the terms of the GNU General Public License as published by the
13+
* Free Software Foundation, either version 3 of the License, or (at your
14+
* option) any later version.
15+
*
16+
* This file is distributed in the hope that it will be useful, but
17+
* WITHOUT ANY WARRANTY; without even the implied warranty of
18+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
19+
* Public License for more details.
20+
*
21+
* You should have received a copy of the GNU General Public License
22+
* along with this program. If not, see http://www.gnu.org/licenses/.
23+
*
24+
* This code is a derivative of work done in EmuFlight Project https://github.com/emuflight/EmuFlight
25+
*
26+
*/
27+
28+
#include "platform.h"
29+
#ifdef USE_SMITH_PREDICTOR
30+
31+
#include <stdbool.h>
32+
#include "common/axis.h"
33+
#include "common/utils.h"
34+
#include "flight/smith_predictor.h"
35+
#include "build/debug.h"
36+
37+
FUNCTION_COMPILE_FOR_SPEED
38+
float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample) {
39+
UNUSED(axis);
40+
if (predictor->enabled) {
41+
predictor->data[predictor->idx] = sample;
42+
43+
predictor->idx++;
44+
if (predictor->idx > predictor->samples) {
45+
predictor->idx = 0;
46+
}
47+
48+
// filter the delayed data to help reduce the overall noise this prediction adds
49+
float delayed = pt1FilterApply(&predictor->smithPredictorFilter, predictor->data[predictor->idx]);
50+
float delayCompensatedSample = predictor->smithPredictorStrength * (sample - delayed);
51+
52+
sample += delayCompensatedSample;
53+
}
54+
return sample;
55+
}
56+
57+
FUNCTION_COMPILE_FOR_SIZE
58+
void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime) {
59+
if (delay > 0.1) {
60+
predictor->enabled = true;
61+
predictor->samples = (delay * 1000) / looptime;
62+
predictor->idx = 0;
63+
predictor->smithPredictorStrength = strength;
64+
pt1FilterInit(&predictor->smithPredictorFilter, filterLpfHz, looptime * 1e-6f);
65+
} else {
66+
predictor->enabled = false;
67+
}
68+
}
69+
70+
#endif

src/main/flight/smith_predictor.h

Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
/*
2+
* This file is part of INAV Project.
3+
*
4+
* This Source Code Form is subject to the terms of the Mozilla Public
5+
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
6+
* You can obtain one at http://mozilla.org/MPL/2.0/.
7+
*
8+
* Alternatively, the contents of this file may be used under the terms
9+
* of the GNU General Public License Version 3, as described below:
10+
*
11+
* This file is free software: you may copy, redistribute and/or modify
12+
* it under the terms of the GNU General Public License as published by the
13+
* Free Software Foundation, either version 3 of the License, or (at your
14+
* option) any later version.
15+
*
16+
* This file is distributed in the hope that it will be useful, but
17+
* WITHOUT ANY WARRANTY; without even the implied warranty of
18+
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
19+
* Public License for more details.
20+
*
21+
* You should have received a copy of the GNU General Public License
22+
* along with this program. If not, see http://www.gnu.org/licenses/.
23+
*
24+
* This code is a derivative of work done in EmuFlight Project https://github.com/emuflight/EmuFlight
25+
*
26+
*/
27+
28+
#pragma once
29+
30+
#include <stdint.h>
31+
#include "common/filter.h"
32+
33+
#define MAX_SMITH_SAMPLES 64
34+
35+
typedef struct smithPredictor_s {
36+
bool enabled;
37+
uint8_t samples;
38+
uint8_t idx;
39+
float data[MAX_SMITH_SAMPLES + 1];
40+
pt1Filter_t smithPredictorFilter;
41+
float smithPredictorStrength;
42+
} smithPredictor_t;
43+
44+
float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample);
45+
void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime);

src/main/target/common.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,7 @@
8686

8787
#define USE_DYNAMIC_FILTERS
8888
#define USE_GYRO_KALMAN
89+
#define USE_SMITH_PREDICTOR
8990
#define USE_EXTENDED_CMS_MENUS
9091
#define USE_HOTT_TEXTMODE
9192

0 commit comments

Comments
 (0)