|
Motor Evaluation Kit NEVC-MCTRL-100-t01-1.0.0
Firmware for NEVB-MCTRL-100-01 for trapezoidal control of BLDC motors using Hall-effect sensors
|
PID controller header file. More...
#include "stdint.h"Go to the source code of this file.
Classes | |
| struct | pidData |
| PID Status. More... | |
Macros | |
| #define | SCALING_FACTOR 256 |
| Scaling division factor for PID controller. | |
| #define | SCALING_FACTOR_ENABLED FALSE |
| Flag indicating whether scaling factor is enabled for PID controller. | |
| #define | MAX_INT 32767 |
| Maximum value of integers. | |
| #define | MAX_LONG 2147483647L |
| Maximum value of long integers. | |
| #define | MAX_I_TERM (MAX_LONG - (2 * (int32_t)MAX_INT)) |
| Maximum value of the I-term. | |
| #define | FALSE 0 |
| FALSE constant. | |
| #define | TRUE (!FALSE) |
| TRUE constant. | |
Typedefs | |
| typedef struct pidData | pidData_t |
| PID Status. | |
Functions | |
| void | PIDInit (int16_t p_factor, int16_t i_factor, int16_t d_factor, pidData_t *pid) |
| Initialisation of PID controller parameters. | |
| uint16_t | PIDController (int16_t setPoint, int16_t processValue, pidData_t *pid_st) |
| PID control algorithm. | |
| void | PIDResetIntegrator (pidData_t *pid_st) |
| Resets the integrator in the PID regulator. | |
PID controller header file.
This file contains defines, typedefs and prototypes for the PID controller.
Definition in file pid.h.
Maximum value of the I-term.
This limits the maximum positive or negative value of the I-term. Changing this value leads to a different integral anti-windup limit. Do not increase this value from its default, as it is already at the limit of the underlying data types.
| #define SCALING_FACTOR 256 |
| #define SCALING_FACTOR_ENABLED FALSE |
Flag indicating whether scaling factor is enabled for PID controller.
The scaling factor can be adjusted by modifying the value of SCALING_FACTOR.
| uint16_t PIDController | ( | int16_t | setPoint, |
| int16_t | processValue, | ||
| pidData_t * | pid_st ) |
PID control algorithm.
Calculates output from set point, process value, and PID status.
| setPoint | Desired value. |
| processValue | Measured value. |
| pid_st | PID status struct. |
Definition at line 54 of file pid.cpp.
| void PIDInit | ( | int16_t | p_factor, |
| int16_t | i_factor, | ||
| int16_t | d_factor, | ||
| pidData_t * | pid ) |
Initialisation of PID controller parameters.
Initialise the variables used by the PID algorithm.
| p_factor | Proportional term. |
| i_factor | Integral term. |
| d_factor | Derivate term. |
| pid | Struct with PID status. |
Definition at line 31 of file pid.cpp.
| void PIDResetIntegrator | ( | pidData_t * | pid_st | ) |
Resets the integrator in the PID regulator.
Calling this function will reset the integrator in the PID regulator.
| pid_st | Pointer to the PID status struct for which the integrator will be reset. |
Definition at line 130 of file pid.cpp.