A Proportional Integral Derivative (PID) controller is an automatically optimized and accurate control system responsible for ensuring that a process remains as close to the desired value as possible regardless of various disruptions. The controller compares the measured process variable \( y(t)\) and a desired Setpoint \( r(t)\) (desired outcome). Based on that comparison, the controller calculates the Proportional, Integral and Derivative terms and adds them to obtain the output signal \( u(t) \) that attempts to minimize the error. This output signal is then used to command the Final Control Element (e.g an actuator) that is in charge of operating the process.
Proportional is used to find out the error between the desired value and actual value and is responsible for the corrective response. Integral is applied to calculate all the past values of error and then integrate them to find out the Integral term. When error is expelled from the system this integral stops increasing. The derivative is used to predict the expected error values in the future based on the present values. Controlling effect can be increased if the system has a rapid rate of change, which is also based on Derivative. Combining all these three operations gives the name Proportional Integral Derivative (PID) Controller.
qLibs provides the qPID implementation, which, apart from the simplified overview representation of the PID controller, it also addresses some practical issues and includes additional features as listed below:
- Derivative filter
- Anti-windup
- Bumpless transfer
- SetPoint weighting
- Auto-tuning
- Additive MRAC
PID Controller approach
The mathematical model and practical loop use a direct control action for all the PID terms, which means an increasing positive error results in an increasing positive control output correction.
The overall control function implemented in qPID_Automatic mode is given by:
\( v(t)= \psi(t)r(t) + [ K_{c}e_{b}(t) + K_{i}\int [ e(t) + c(t-1) ]dt + K_{d}f_{d}(t) ] \) \( u(t) = \text{Sat}[ v(t), u_{min}, u_{max} ]\) where \(r(t)\) is the set-point, \(y(t)\) the process output, \( e(t) \) its the error \(K_{c},K_{i},K_{d}\) the PID gains respectively and \(u(t)\) the control action.
\(\psi(t)\) is the adaptive gain from the additive MRAC (later explained)
As shown above, the derivative term \(f_{d}(t)\) is the output of a low-pass filter that takes the raw derivative as input.
\( f_{d}(t) = \text{LPF}[ \frac{de_{c}(t)}{dt} ]\) and \( c(t)\), the saturation feedback for the anti-windup, with \(K_{w}\) as the adjustment parameter.
\( c(t) = K_{w}[ u(t) - v(t) ] \)
qpid
PID Implementation
Manual Mode
When the operation mode is changed to qPID_Manual, the feedback is disconnected and the controller works in open loop being commanded by the manual input \( m(t) \). Since the controller is a dynamic system, it is necessary to make sure that the state of the system is correct when switching the controller between manual and automatic mode. When the system is in manual mode, the control algorithm produces a control signal that may be different from the manually generated control signal. It is necessary to make sure that the two outputs coincide at the time of switching. This is called bumpless transfer and it's given by
\( v(t) = \int [ K_{T}m(t) + c(t-1) ]dt\)
Creating a PID Controller
Before you start using a controller, it must be instantiated first via the qPID_controller_t type and then configured using the qPID_Setup() API, where you can define the PID gains and time step.
Example: Instantiating an configuring a PID controller:
const float kc = 1.0f, ki = 0.1f, kd = 0.0f;
const float dt = 0.01f;
int ret;
if ( 0 == ret ) {
}
int qPID_Setup(qPID_controller_t *const c, const float kc, const float ki, const float kd, const float dt)
Setup and initialize the PID controller instance.
Definition qpid.c:25
A PID controller object.
Definition qpid.h:91
Using the controller
The following example illustrates how a PID controller can be used to regulate the speed of a DC motor. PID control operates on a separate task running periodically at a rate of 50mS. The speed measurement is read through an analog input and then scaled to the appropriate units (RPM). The qPID_Control() function will be in charge of computing the control action and updating the internal states of the controller. Then, the control output gets scaled back in order to send the control command by using the PWM(Pulse Width Modulation) module.
Example: Speed control using a PID controller:
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "bsp.h"
#include "qpid.h"
const TickType_t dt = 50;
void xTaskPIDspeedControl( void *arg );
float SetPoint = 300.0f;
void xTaskPIDspeedControl( void *arg )
{
float processMeasurement;
float controlOutput;
for ( ;; ) {
processMeasurement = BSP_ScaletoSpeed ( BSP_AnalogRead( BSP_AI_SPEED_CHANNEL ) );
controlOutput =
qPID_Control( controller, SetPoint, processMeasurement );
BSP_PWMSet( BSP_AO_SPEED_PWM_CHANNEL, BSP_ScaletoPWM( controlOutput ) );
vTaskDelay( dt / portTICK_RATE_MS) ;
}
}
int main( int argc, char *argv[] )
{
int ret;
BSP_SystemInit();
ret =
qPID_Setup( &speedControl, 1, 0.1, 0, (
float)dt/1000.0f );
if ( 0 == ret ) {
puts( "ERROR: Cant configure PID controller" );
}
xTaskCreate( xTaskPIDspeedControl, "speedControl", 1024, &speedControl, configMAX_PRIORITIES - 1 ,NULL );
vTaskStartScheduler();
for( ;; );
return EXIT_SUCCESS;
}
float qPID_Control(qPID_controller_t *const c, const float w, const float y)
Computes the control action for given PID controller instance.
Definition qpid.c:265
int qPID_SetSaturation(qPID_controller_t *const c, const float min, const float max)
Setup the output saturation for the PID controller.
Definition qpid.c:136
Additive MRAC (Model Reference Adaptive Control)
Model Reference Adaptive Control (MRAC) is a strategy where the controller of the closed-loop is adapted by an adjustment mechanism, which takes \( y_{m}(t) \) from a reference model as input and tries to adjust the controller output \(v(t)\). The adjustment mechanism used by qPID is the enhanced MIT-rule approach, which adapts a feed-forward gain by the error between the system \( y(t) \) and a reference model \( y_{m}(t) \), therefore is the so-called Gradient approach.
\( e_{m}(t) = y(t) - y_{m}(t)\) \( \delta(t) = -\gamma \frac{ e_{m}(t) y_{m}(t) }{ \beta + y_{m}^{2}(t) } \) where \(\gamma(t)\) is the adaptation gain and \(\beta(t)\) is introduced to remove the problem of the possible division by zero if \(y_{m}^{2}(t) \) gets too small.
The MRAC adaptation is then computed by integrating the \(\delta(t)\) term as follows:
\( \psi(t) = \int [ \delta(t) + c(t) ] dt \) This method can be used to adapt to slower changes but can become unstable for abrupt changes to the system. Therefore, this implementation uses a so-called modified MRAC (M-MRAC) where the adaptation is later added to a PID controller, being the MRAC the additive loop.
Abrupt changes to the system are absorbed by the PID controller, while the change of the dynamics will still be handled by the MIT gain \(\psi(t)\). This results in the equation of the control function presented at the beginning of this section.
To use the additive MRAC, you should first instantiate a reference model and then, enable the MRAC by using the qPID_SetMRAC() API. Here, you must provide a pointer to the output of the reference model and the adaptation gain \(\gamma(t)\)
Example: Speed control with PID controller with an additive MRAC:
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "bsp.h"
#include "qpid.h"
#include "qltisys.h"
#define REF_MODEL_ORDER ( 1 )
const TickType_t dt = 50;
void xTaskPIDspeedControl( void *arg );
void xTaskPIDspeedControl( void *arg )
{
float num[ REF_MODEL_ORDER+1 ] = { 0.0f, 1.0f, };
float den[ REF_MODEL_ORDER+1 ] = { 3.0f, 1.0f, };
float processMeasurement;
float SetPoint = 300.0f;
float refmodel_output = 0.0f;
float controlOutput = 0.0f;
qLTISys_Setup( &ref_model, num, den, x, 0, REF_MODEL_ORDER+1, (
float)dt/1000.0f ) );
for ( ;; ) {
processMeasurement = BSP_ScaletoSpeed ( BSP_AnalogRead( BSP_AI_SPEED_CHANNEL ) );
controlOutput =
qPID_Control( controller, SetPoint, processMeasurement );
BSP_PWMSet( BSP_AO_SPEED_PWM_CHANNEL, BSP_ScaletoPWM( controlOutput ) );
vTaskDelay( dt / portTICK_RATE_MS) ;
}
}
int main( int argc, char *argv[] )
{
int ret;
BSP_SystemInit( );
ret =
qPID_Setup( &speedControl, 1, 0.1, 0, (
float)dt/1000.0f );
if ( 0 == ret ) {
puts( "ERROR: Cant configure PID controller" );
}
xTaskCreate( xTaskPIDspeedControl, "speedControl", 1024, &speedControl, configMAX_PRIORITIES - 1 ,NULL );
vTaskStartScheduler();
for( ;; );
return EXIT_SUCCESS;
}
float qLTISys_Excite(qLTISys_t *const sys, float u)
Drives the LTI system recursively using the input signal provided.
Definition qltisys.c:61
int qLTISys_Setup(qLTISys_t *const sys, float *num, float *den, void *x, const size_t nb, const size_t na, const float dt)
Setup and initialize an instance of a LTI system.
Definition qltisys.c:155
int qPID_SetMRAC(qPID_controller_t *const c, const float *modelRef, const float gamma)
Enable the additive MRAC(Model Reference Adaptive Control) feature.
Definition qpid.c:237
A LTI system object.
Definition qltisys.h:52
Autotuning
Autotuning can eliminate much of the trial and error of a manual tuning approach, especially if you do not have a lot of loop tuning experience. Performing the autotuning procedure will get the tuning parameters close to their optimal values, but additional manual tuning may be required to get the tuning parameters to their optimal values.
The Autotune feature for the controller will only run for a limited amount of time after it gets enabled. In other words, autotuning does not run continuously during operation. Whenever there is a substantial change in the process dynamics, the tuning process will need to be repeated in order to derive new gains required for optimal control.
Autotuning is performed by using the following recursive algorithm:
\( L(t) = \frac{ P(t-1)\phi }{ \lambda + \phi^{T}P(t-1)\phi } \) \(\theta(t) = \theta(t-1) + L[ y(t) - \phi^{T}\theta(t) ] \) \( P(t) = \lambda^{-1}[ I - L(t)+\phi^{T}]P(t-1) \) \( \theta(t) = \begin{bmatrix} \theta_{1}(t) & \theta_{2}(t) \end{bmatrix}^T \) and \( \phi(t) = \begin{bmatrix} -y(t-1) & u(t-1) \end{bmatrix}^T \) \( g(t) = \frac{ (1 - \mu)\theta_{2}(t) }{ 1 + \theta_{1} } + \mu g(t-1) \) \( \tau(t) = \frac{ ( \mu - 1 )dt }{ ln( |\theta_{1}| ) } + \mu \tau(t-1) \) \( K_{c}(t) = \alpha \frac{ r_{2} \tau(t) }{ g(t)dt } \) \( K_{i}(t) = \alpha \frac{ g(t)[ 0.54 + 0.33r_{1} ] }{ r_{2}dt } \) \( K_{c}(t) = \alpha \frac{ K_{c}(t)dt }{ r_{2} } \) where \( r_{1} = dt/\tau(t) \) and \( r_{2} = 1.35 + 0.25r_{1} \)
and the remaining parameters \(\mu\), \(\alpha\), \(\lambda\) are internally computed for best performance.
Autotuning Usage
In order to use the autotuner, you must first instantiate the qPID_AutoTuning_t object and bind it to a previously configured PID controller by using the qPID_BindAutoTuning().
After this, you can enable autotuning via qPID_EnableAutoTuning() for a defined number of intervals. When the autotune ends, the resulting PID gains will be applied to the bounded controller.
Example: Speed control with PID controller and autotuning:
This example takes advantage of the FreeRTOS task notifications to enable the autotuning when a rising edge is detected on a certain digital input. Autotuning is enabled for 5 sec. Note that the setpoint is briefly modified during this process to stimulate the process. Upon completion, the setpoint is restored to its original value.
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "bsp.h"
#include "qpid.h"
#define REF_MODEL_ORDER ( 1 )
const TickType_t dt = 50;
void xTaskPIDspeedControl( void *arg );
TaskHandle_t pid_task;
void gpio_Int_Handler( void )
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
vTaskNotifyGiveFromISR( pid_task, &xHigherPriorityTaskWoken);
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
HAL_GPIO_ClearStatusFlag();
}
void xTaskPIDspeedControl( void *arg )
{
float processMeasurement;
float SetPoint = 300.0f;
float tmpSetPoint = 320.0f;
float *p_setpoint = &SetPoint;
float refmodel_output = 0.0f;
float controlOutput = 0.0f;
uint32_t notification_autotune_enable;
qLTISys_Setup( &ref_model, num, den, x, 0, REF_MODEL_ORDER+1, (
float)dt/1000.0f ) );
for ( ;; ) {
notification_autotune_enable = ulTaskNotifyTake( pdTRUE, 0 );
if ( notification_autotune_enable ) {
p_setpoint = &tmpSetPoint;
}
p_setpoint = &SetPoint;
}
processMeasurement = BSP_ScaletoSpeed ( BSP_AnalogRead( BSP_AI_SPEED_CHANNEL ) );
controlOutput =
qPID_Control( controller, *p_setpoint, processMeasurement );
BSP_PWMSet( BSP_AO_SPEED_PWM_CHANNEL, BSP_ScaletoPWM( controlOutput ) );
vTaskDelay( dt / portTICK_RATE_MS) ;
}
}
int main( int argc, char *argv[] )
{
int ret;
BSP_SystemInit( );
HAL_GPIO_Enable( GPIO12, GPIO_INPUT );
HAL_GPIO_SetInterruptMode( GPIO12, RISING_EDGE );
HAL_GPIO_EnableInterrupts( );
ret =
qPID_Setup( &speedControl, 1, 0.1, 0, (
float)dt/1000.0f );
if ( 0 == ret ) {
puts( "ERROR: Cant configure PID controller" );
}
xTaskCreate( xTaskPIDspeedControl, "speedControl", 1024, &speedControl, configMAX_PRIORITIES - 1 , &pid_task );
vTaskStartScheduler();
for( ;; );
return EXIT_SUCCESS;
}
int qPID_AutoTuningComplete(const qPID_controller_t *const c)
Verifies that the auto tuning process has finished with new gains set on the controller.
Definition qpid.c:480
int qPID_BindAutoTuning(qPID_controller_t *const c, qPID_AutoTuning_t *const at)
Binds the specified instance to enable the PID controller auto tuning algorithm.
Definition qpid.c:320
int qPID_EnableAutoTuning(qPID_controller_t *const c, const uint32_t tEnable)
Set the number of time steps where the auto tuner algorithm will modify the controller gains.
Definition qpid.c:358
A PID Auto-tuning object.
Definition qpid.h:68