This repository implements a PID (Proportional-Integral-Derivative) controller designed to regulate the speed of an auto-following kart with a leader robot. The implementation includes the PID controller logic, a car simulation, and a framework for testing various PID configurations.
This header file implements a PID controller that includes traditional PID control logic along with enhancements such as adaptive gain adjustment, adaptive integral term, error history management, and additional derivative term. It is also designed to be compatible with both Arduino and non-Arduino environments.
The header is designed to be compatible with both Arduino and non-Arduino environments. This allows developers to use the same PID controller implementation across different platforms.
Conditional Compilation:
#ifdef ARDUINO
#include <Arduino.h>
#include <math.h>
#define to_string(a) String(a)
#else
#include <cmath>
#include <string>
#define String string
using namespace std;
#endif
The traditional PID controller is defined by the following equation:
Where:
-
$u(t)$ is the control output. -
$e(t)$ is the error at time$t$ , defined as the difference between the desired value and the measured value. -
$K_p$ ,$K_i$ , and$K_d$ are the proportional, integral, and derivative gains, respectively.
The proportional gain
Where:
$eDP = e(t) \times \frac{de(t)}{dt}$ -
$eDP_m$ is a threshold that determines when to adjust the proportional gain. -
$eDP_a$ is the adjustment factor that scales the change in$K_p$ based on the error’s derivative.
The key idea behind this adjustment is to increase the proportional gain when the system is experiencing a large error combined with a significant rate of change, which could indicate an approaching overshoot or oscillation. Conversely, if the error is decreasing but remains large, it may reduce the proportional gain to prevent excessive correction, allowing the system to stabilize more smoothly.
Integral control is essential for eliminating steady-state error; however, it can lead to issues like integral windup, where the integral term accumulates excessively during periods of sustained error. To mitigate this, the integral gain
Where:
$ap = e^{-\frac{\text{amp}}{\text{maxAmp}}}$ -
$rTiM$ is a constant that relates to the desired integral time constant.
The variable
Inspired by the Ziegler–Nichols tuning method, the implementation maintains a history of past errors and their timestamps to calculate the derivative and integral terms accurately. This history management is crucial for two main reasons:
-
Deriving the Rate of Change: The derivative term requires knowledge of how fast the error is changing. By storing previous error values in a linked list, we can accurately compute the change in error over time (
$\frac{de(t)}{dt}$ ):
- Integral Calculation: The integral of the error is accumulated over time, enabling the controller to respond to persistent deviations from the setpoint:
Using a linked list allows for efficient management of this error history. As new errors are added, older entries can be pruned to ensure that only relevant data is retained, which helps avoid excessive memory usage and keeps the calculations focused on the most recent behavior of the system.
In addition to the standard derivative term
Where:
-
$TddM$ is a multiplier that adjusts the impact of the second derivative term.
The inclusion of
- Data: Holds the time difference (
dt
) and error value (e
). - Node: Represents an element in the linked list, containing
Data
and a pointer to the previous node. - List: Manages the linked list, holding pointers to the head and tail nodes and the size of the list.
The PID
class encapsulates the PID control logic. It includes:
-
Member Variables:
- Control gains:
Kp
,Ki
,Kd
,Kdd
(additional derivative term). - State variables:
preE
,preDv
,intg
,preOut
, andpreT
for storing previous error, derivative, integral term, last output, and last timestamp, respectively. dtXs
: An instance ofList
to maintain historical error data.
- Control gains:
-
Constructor: Initializes the PID parameters and state variables.
-
Update Method:
- Takes the current error and timestamp, computes the control output, and updates the internal state.
- Implements logic for calculating the adaptive gains, managing error history, and generating the control signal.
This header file includes a Car
class for simulating the motion of a car, a PID controller for adjusting the speed of an auto-following kart based on the distance to a leader car, and several utility functions for data processing and results management.
The Car
class represents a simple vehicle model with basic motion dynamics. It includes attributes for speed and position, as well as methods to update these attributes.
The pidDebug
function is a utility for logging messages related to PID control operations.
double sum_last_squared(const std::vector<double> &v, double prop)
Calculates the sum of squares of the last n * prop
elements of the provided vector v
.
vector<double> velocities(int steps)
Generates a vector of velocity values over a specified number of simulation steps, simulating different phases of motion (acceleration, deceleration, and adjustments).
vector<double> test(double maxIntTm, double maxAmp, double minKp, double maxKp, double rTiM, double TdM, double TddM, double eDPm, double eDPa, unsigned long session, double Kp, double preE = 0, unsigned long preT = 0, double timeInterval = 10, int steps = 1000)
This function simulates the interaction between a leader car and an auto-following kart using a PID controller to adjust the follower's speed based on the distance to the leader.
-
Parameters:
double maxIntTm
: Maximum integral time constant.double maxAmp
: Maximum amplitude of control output.double minKp
: Minimum proportional gain.double maxKp
: Maximum proportional gain.double rTiM
: Reference time interval multiplier.double TdM
: Derivative time multiplier.double TddM
: Second derivative time multiplier.double eDPm
: Maximum error derivative proportionality factor.double eDPa
: Error derivative adjustment factor.unsigned long session
: Session identifier for logging purposes.double Kp
: Initial proportional gain.double preE
: Previous error value (optional, defaults to 0).unsigned long preT
: Previous time value (optional, defaults to 0).double timeInterval
: Time interval for each step of simulation (default is 10).int steps
: Total number of simulation steps (default is 1000).
-
Returns: A vector containing the distances between the leader and follower over time.
struct pidTest
{
double maxIntTm, maxAmp, minKp, maxKp, rTiM, TdM, TddM, eDPm, eDPa;
unsigned long session;
double Kp, result;
};
The pidTest
structure is used to store parameters for PID testing, along with the result of the simulation.
bool write_results(const vector<pidTest> &data, const string &filename)
Writes the results of PID tests to a CSV file for analysis.
A structure to define the range of parameters for optimization.
- Attributes:
double start
: The starting value of the parameter range.double end
: The ending value of the parameter range.double step
: The increment step for the parameter.
This header file defines the optimization functions and structures used to optimize the parameters of a PID controller in a car simulation without multi-threaded processing.
Optimizes the parameters of the PID controller based on the provided ranges and writes results to a CSV file.
-
Parameters:
vector<ParameterRange> ranges
: A vector containing the ranges of parameters to optimize.
-
Returns:
int
: ReturnsEXIT_SUCCESS
(0) if optimization completes successfully, otherwise returnsEXIT_FAILURE
.
This header file defines the optimization functions and structures used to optimize the parameters of a PID controller in a car simulation with multi-threaded processing.
Optimizes the parameters of the PID controller based on the provided ranges and writes results to a CSV file.
-
Parameters:
vector<ParameterRange> ranges
: A vector containing the ranges of parameters to optimize.
-
Returns:
int
: ReturnsEXIT_SUCCESS
(0) if optimization completes successfully, otherwise returnsEXIT_FAILURE
.
The code file demonstrates the usage of the optimization.hpp
(or optimization_multithread.hpp
) header file to perform parameter optimization for a PID controller. It defines a set of parameter ranges and calls the optimize
function to evaluate different combinations of parameters.
Note that steps can't be zero or the program won't stop.
The wooden board serves as the support structure of the auto-following kart that connects and props the components such as an Arduino board, an Omni wheel, a breadboard, 2 wheels, and 2 motors.
The 3D design file is assets/board.step.
Here's the photo of the cut wooden board:
The development of this PID (Proportional-Integral-Derivative) controller project is rooted in control theory, a field of engineering that focuses on the behavior of dynamic systems. What makes us take the initiative is the auto-following kart lesson in our living technology class. We aim to make an auto-following kart from scratch with Arduino and wooden boards and make it as quality as possible on a constrained budget.
The development of this PID (Proportional-Integral-Derivative) controller project is rooted in control theory, a field of engineering that focuses on the behavior of dynamic systems. PID controllers are a cornerstone of modern control systems. They are designed to automatically adjust system outputs based on feedback to minimize error, allowing for precise control of dynamic systems. The PID controller operates based on three fundamental components:
-
Proportional Control (P): Responds proportionally to the current error value, providing immediate correction based on how far the system is from the desired state.
-
Integral Control (I): Addresses accumulated past errors, ensuring that the system reaches the desired state even if there are persistent biases.
-
Derivative Control (D): Predicts future errors based on the rate of change of the error, providing a damping effect to reduce overshoot and oscillation.
The tuning of these parameters is crucial for achieving optimal performance. The traditional Ziegler–Nichols tuning method has served as a foundational approach for many engineers, providing empirical guidelines for setting PID parameters based on system behavior.
Arduino boards offer an accessible platform for students and hobbyists to experiment with hardware and software integration, facilitating hands-on learning experiences in technology classes.
In living technology classes, we engage with Arduino to build auto-following kart projects that require real-time control systems. This scenario highlights the importance of tuning PID controllers to achieve desired behaviors in robotics and automotive systems.
This PID controller serves as an imperative part of our auto-following kart. We use it to achieve a stable distance between the auto-following kart and the leader kart, in our case, a cleaning robot.
The development of the PID controller and its associated simulation framework has been an iterative process, marked by continuous enhancement and refinement.
The journey began with a simple implementation of the traditional PID controller. The focus was on creating a basic class structure in C++ that encapsulated the PID logic, allowing for straightforward application in simulations.
- Key Features:
- Basic PID calculations.
- Initial support for both Arduino and non-Arduino environments through conditional compilation.
As the initial implementation was tested, several limitations became apparent, particularly regarding responsiveness and stability. This prompted the incorporation of advanced features such as:
-
Adaptive Gain Adjustment: Inspired by the need for dynamic responsiveness, the proportional gain
$K_p$ was made adaptable based on the error's rate of change. This enhancement allowed for better handling of transient behaviors in the system. -
Adaptive Integral Term: To mitigate integral windup, the integral gain
$K_i$ was adjusted based on observed error amplitude. This feature improved system stability during sustained error conditions.
To accurately compute the integral and derivative terms, a robust error history management system was implemented. This system utilized a linked list structure to store past error values and timestamps, enabling precise calculations for both the integral and derivative components. The integration of error history management was crucial for implementing more advanced tuning strategies, inspired by established control theory practices.
Recognizing the need for improved damping characteristics, an additional derivative term
With the PID logic in place, attention turned to building a comprehensive simulation framework to test various PID configurations. The introduction of the Car
class for simulating follower and leader vehicles added a practical context for evaluating PID performance in a dynamic environment.
- PID Testing Function: A dedicated function was developed to simulate the interaction between the leader and follower karts, providing insights into how different PID parameters affected system behavior.
To facilitate further exploration of PID parameter tuning, optimization functions were integrated. Utilizing multi-threading allowed for the concurrent evaluation of multiple parameter combinations, greatly enhancing the testing efficiency. The optimization framework also included mechanisms for result logging and progress tracking, making it easier to analyze and visualize outcomes.
Contributions are welcome! If you have ideas for improvements or optimizations, please fork the repository and create a pull request.
This project is licensed under the AGPL License. See the LICENSE.md file for details.