Skip to content

Commit

Permalink
Merge pull request #6900 from iNavFlight/dzikuvx-smith-predictor
Browse files Browse the repository at this point in the history
Smith Predictor on PID measurement
  • Loading branch information
DzikuVx committed Apr 30, 2021
2 parents c098bde + b265369 commit 5a4aaed
Show file tree
Hide file tree
Showing 9 changed files with 191 additions and 2 deletions.
3 changes: 3 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -498,6 +498,9 @@
| 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] |
| smartport_master_halfduplex | ON | | | |
| smartport_master_inverted | OFF | | | |
| smith_predictor_delay | 0 | 0 | 8 | Expected delay of the gyro signal. In milliseconds |
| smith_predictor_lpf_hz | 50 | 1 | 500 | Cutoff frequency for the Smith Predictor Low Pass Filter |
| smith_predictor_strength | 0.5 | 0 | 1 | The strength factor of a Smith Predictor of PID measurement. In percents |
| 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 |
| srxl2_baud_fast | ON | | | |
| srxl2_unit_id | 1 | 0 | 15 | |
Expand Down
2 changes: 2 additions & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -320,6 +320,8 @@ main_sources(COMMON_SRC
flight/imu.h
flight/kalman.c
flight/kalman.h
flight/smith_predictor.c
flight/smith_predictor.h
flight/mixer.c
flight/mixer.h
flight/pid.c
Expand Down
1 change: 1 addition & 0 deletions src/main/build/debug.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,5 +83,6 @@ typedef enum {
DEBUG_FW_D,
DEBUG_IMU2,
DEBUG_ALTITUDE,
DEBUG_SMITH_COMPENSATOR,
DEBUG_COUNT
} debugType_e;
24 changes: 23 additions & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,8 @@ tables:
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D", "IMU2", "ALTITUDE"]
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D", "IMU2", "ALTITUDE",
"SMITH_COMPENSATOR"]
- name: async_mode
values: ["NONE", "GYRO", "ALL"]
- name: aux_operator
Expand Down Expand Up @@ -2061,6 +2062,27 @@ groups:
field: fixedWingLevelTrim
min: -10
max: 10
- name: smith_predictor_strength
description: "The strength factor of a Smith Predictor of PID measurement. In percents"
default_value: 0.5
field: smithPredictorStrength
condition: USE_SMITH_PREDICTOR
min: 0
max: 1
- name: smith_predictor_delay
description: "Expected delay of the gyro signal. In milliseconds"
default_value: 0
field: smithPredictorDelay
condition: USE_SMITH_PREDICTOR
min: 0
max: 8
- name: smith_predictor_lpf_hz
description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
default_value: 50
field: smithPredictorFilterHz
condition: USE_SMITH_PREDICTOR
min: 1
max: 500

- name: PG_PID_AUTOTUNE_CONFIG
type: pidAutotuneConfig_t
Expand Down
42 changes: 41 additions & 1 deletion src/main/flight/pid.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ FILE_COMPILE_FOR_SPEED
#include "flight/rpm_filter.h"
#include "flight/secondary_imu.h"
#include "flight/kalman.h"
#include "flight/smith_predictor.h"

#include "io/gps.h"

Expand Down Expand Up @@ -109,6 +110,8 @@ typedef struct {
bool itermFreezeActive;

biquadFilter_t rateTargetFilter;

smithPredictor_t smithPredictor;
} pidState_t;

STATIC_FASTRAM bool pidFiltersConfigured = false;
Expand Down Expand Up @@ -159,7 +162,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn;
static EXTENDED_FASTRAM bool levelingEnabled = false;
static EXTENDED_FASTRAM float fixedWingLevelTrim;

PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 1);
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 2);

PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.bank_mc = {
Expand Down Expand Up @@ -297,6 +300,12 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
#endif

.fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT,

#ifdef USE_SMITH_PREDICTOR
.smithPredictorStrength = SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT,
.smithPredictorDelay = SETTING_SMITH_PREDICTOR_DELAY_DEFAULT,
.smithPredictorFilterHz = SETTING_SMITH_PREDICTOR_LPF_HZ_DEFAULT,
#endif
);

bool pidInitFilters(void)
Expand Down Expand Up @@ -349,6 +358,30 @@ bool pidInitFilters(void)
}
}

#ifdef USE_SMITH_PREDICTOR
smithPredictorInit(
&pidState[FD_ROLL].smithPredictor,
pidProfile()->smithPredictorDelay,
pidProfile()->smithPredictorStrength,
pidProfile()->smithPredictorFilterHz,
getLooptime()
);
smithPredictorInit(
&pidState[FD_PITCH].smithPredictor,
pidProfile()->smithPredictorDelay,
pidProfile()->smithPredictorStrength,
pidProfile()->smithPredictorFilterHz,
getLooptime()
);
smithPredictorInit(
&pidState[FD_YAW].smithPredictor,
pidProfile()->smithPredictorDelay,
pidProfile()->smithPredictorStrength,
pidProfile()->smithPredictorFilterHz,
getLooptime()
);
#endif

pidFiltersConfigured = true;

return true;
Expand Down Expand Up @@ -1052,6 +1085,13 @@ void FAST_CODE pidController(float dT)
pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget);
}
#endif

#ifdef USE_SMITH_PREDICTOR
DEBUG_SET(DEBUG_SMITH_COMPENSATOR, axis, pidState[axis].gyroRate);
pidState[axis].gyroRate = applySmithPredictor(axis, &pidState[axis].smithPredictor, pidState[axis].gyroRate);
DEBUG_SET(DEBUG_SMITH_COMPENSATOR, axis + 3, pidState[axis].gyroRate);
#endif

DEBUG_SET(DEBUG_PID_MEASUREMENT, axis, pidState[axis].gyroRate);
}

Expand Down
5 changes: 5 additions & 0 deletions src/main/flight/pid.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,11 @@ typedef struct pidProfile_s {
#endif

float fixedWingLevelTrim;
#ifdef USE_SMITH_PREDICTOR
float smithPredictorStrength;
float smithPredictorDelay;
uint16_t smithPredictorFilterHz;
#endif
} pidProfile_t;

typedef struct pidAutotuneConfig_s {
Expand Down
70 changes: 70 additions & 0 deletions src/main/flight/smith_predictor.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*
* This code is a derivative of work done in EmuFlight Project https://github.com/emuflight/EmuFlight
*
*/

#include "platform.h"
#ifdef USE_SMITH_PREDICTOR

#include <stdbool.h>
#include "common/axis.h"
#include "common/utils.h"
#include "flight/smith_predictor.h"
#include "build/debug.h"

FUNCTION_COMPILE_FOR_SPEED
float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample) {
UNUSED(axis);
if (predictor->enabled) {
predictor->data[predictor->idx] = sample;

predictor->idx++;
if (predictor->idx > predictor->samples) {
predictor->idx = 0;
}

// filter the delayed data to help reduce the overall noise this prediction adds
float delayed = pt1FilterApply(&predictor->smithPredictorFilter, predictor->data[predictor->idx]);
float delayCompensatedSample = predictor->smithPredictorStrength * (sample - delayed);

sample += delayCompensatedSample;
}
return sample;
}

FUNCTION_COMPILE_FOR_SIZE
void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime) {
if (delay > 0.1) {
predictor->enabled = true;
predictor->samples = (delay * 1000) / looptime;
predictor->idx = 0;
predictor->smithPredictorStrength = strength;
pt1FilterInit(&predictor->smithPredictorFilter, filterLpfHz, looptime * 1e-6f);
} else {
predictor->enabled = false;
}
}

#endif
45 changes: 45 additions & 0 deletions src/main/flight/smith_predictor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*
* This code is a derivative of work done in EmuFlight Project https://github.com/emuflight/EmuFlight
*
*/

#pragma once

#include <stdint.h>
#include "common/filter.h"

#define MAX_SMITH_SAMPLES 64

typedef struct smithPredictor_s {
bool enabled;
uint8_t samples;
uint8_t idx;
float data[MAX_SMITH_SAMPLES + 1];
pt1Filter_t smithPredictorFilter;
float smithPredictorStrength;
} smithPredictor_t;

float applySmithPredictor(uint8_t axis, smithPredictor_t *predictor, float sample);
void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength, uint16_t filterLpfHz, uint32_t looptime);
1 change: 1 addition & 0 deletions src/main/target/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@

#define USE_DYNAMIC_FILTERS
#define USE_GYRO_KALMAN
#define USE_SMITH_PREDICTOR
#define USE_EXTENDED_CMS_MENUS
#define USE_HOTT_TEXTMODE

Expand Down

0 comments on commit 5a4aaed

Please sign in to comment.