1. Introduction
Direct current motors (DC motors) are a well-known type of electric motor that convert electrical energy into mechanical energy. DC motors find many applications across a wide range of industries and fields due to their ease of use, simplicity, controllability, and versatility. These motors can be found in various automotive applications, industrial conveyor belt systems, robotic arms, CNC machines, and various actuating and power systems, as well as in medical applications or in everyday devices like home appliances, consumer electronics and so forth. The literature on electrical machinery is vast, see, e.g., [
1,
2,
3,
4,
5,
6].
DC motors operate on the physical principle of Lorentz force, where a current-carrying conductor placed in a magnetic field experiences a force:
, where
I is the DC current flowing through the conductor part with the infinitesimal length of
, and
is the magnetic flux density [
7,
8]. This force results in the torque that causes the rotating part (rotor) to turn, resulting in mechanical motion.
The homogeneous magnetic field can be generated by windings supplied by DC current or by magnets arranged around the rotating part. The part of the motor where these windings or the magnets are placed is called the stator [
1,
2,
3].
A frame made of wire is placed in a homogeneous magnetic field as shown in
Figure 1 [
9]. The current
I is flowing through the wire of the frame. In this special case, when the vectors
and
are perpendicular to each other, the Lorentz force equation has the simple form of
, where
l is the side length of the wireframe, and
is the constant magnetic flux density amplitude. The Lorentz force is constant, and perpendicular to the magnetic field and the frame side, too.
Then, a torque
T is acting on the frame:
, where
d is the distance between the two sides of the frame, and
is the angle between the frame and the horizontal (
in
Figure 1). Since the frame can rotate, meaning that the angle can change, consequently the angle is a function of time.
Figure 1 shows only one frame for simplicity. The rotor in a real DC motor consists of a number of frames, which are rotated relative to each other and all frames are connected to the so-called commutator [
1,
2,
3,
9].
Since the motor has several frames [
1,
2,
3,
9], thanks to the commutators,
, because there is usually a frame with approximately the maximum value of the torque, and
can be used as an approximation. In other words, torque is proportional to the current, and
K is the motor constant depending on the magnetic flux and the motor dimensions (here
).
The frame is rotated by the above-mentioned torque. The voltage is induced according to Lenz law, i.e., to the motion: , where is the flux of one frame, i.e., . Since the motor is built up by several frames, can be supposed, and is the angular velocity of the rotor.
The motor constant K is supposed to be a constant value in this paper. It is a motor parameter identified by measurements.
As mentioned, the DC motor consists of several rotating frames [
1,
2,
3,
9], and only one frame acts at a moment. The switching between the frames can be realized by the commutator.
There are different types of DC motors [
1,
2,
3,
10], including brushed DC motors and brushless DC motors (BLDC motors). Brushed motors have brushes and a commutator to control the direction of current flow in the motor windings. Simple and economical brushed DC motors require maintenance due to brush wear and generate more electrical noise. Brushless motors use electronic commutation instead of brushes. They typically have a higher efficiency, longer lifespan, and lower maintenance requirements compared to brushed DC motors.
DC motors can be controlled in various ways, including voltage control, pulse-width modulation (PWM), or by using specialized motor controllers or drivers. These control methods allow for precise speed and torque control and precise positioning. Generally, feedback control systems use sensors to measure parameters such as motor speed, torque, or position and provide feedback to the motor controller to adjust the operation accordingly in a closed-loop system. Feedback control enables the precise control of the motor performance and allows it to maintain the desired speed, torque, or position even in the presence of disturbances or changes in operating conditions. The literature on drive is also vast, e.g., [
4,
5,
6,
10].
To design control systems [
11,
12,
13,
14], model based approach is the modern way [
15,
16,
17,
18,
19,
20,
21], which is followed in this paper. The studied controllers are the PID controller family [
9,
17,
18,
19,
20,
21,
22,
23,
24,
25,
26,
27,
28,
29] and the state feedback controllers [
10,
16,
18,
19,
21,
30,
31]. PID controller is a type of feedback control system widely used in industrial and automation applications to regulate the behavior of dynamic systems. PID stands for proportional, integral, and derivative, which are the three terms that make up the control action. The controller gains can be set up by the phase margin, for example. State feedback control is a modern technique used in control. The behavior of a dynamic system is controlled by applying feedback based on the state variables of the system, i.e., state feedback control uses measurements of the system’s internal state variables. Various control design techniques, such as pole placement, linear quadratic regulator, and optimal control methods can be used to determine the appropriate feedback gains. The so-called state observer is also studied in this work, which is used to estimate the internal state variables of the dynamic system based on available and deterministic input and output measurements, i.e., an observer estimates the state variables based on the system inputs and outputs. The Kalman filter as an optimal state estimator is also implemented to estimate the state of a dynamic system based on noisy measurements of the system’s stochastic input and output. Here, only linear control methods and full-order observers/estimators are shown.
Modeling the dynamic behavior of a DC motor involves describing its electrical and mechanical characteristics mathematically [
9,
17,
20,
21,
31,
32,
33,
34,
35,
36,
37,
38,
39,
40]. The dynamic model typically considers the interaction between electrical quantities (voltage and current) and mechanical quantities (torque, speed, and position) in the form of a system of coupled differential equations in the time domain or applying the transfer function between the input and output of the system in the frequency domain or in the Laplace transform domain. Differential equation representation is also called the state space model. Linear and nonlinear models are also shown in the literature, here only linear modeling is studied, and all the nonlinearities are neglected. Major nonlinearity is the dead-zone type friction [
29,
35,
36,
37,
39,
41,
42,
43].
The dynamic model will be described step by step in
Section 2. State feedback controller design is based on the state space representation of the dynamic system, while PID controllers are designed by using the transfer function. PID controllers and state feedback-based controllers are presented and designed separately in this work.
After motor modeling, the system of differential equations or the transfer function can be set up by system identification. The offline (batch method) or online (real-time method) least square parameter estimation are core methods to model identification [
30,
32,
33,
35,
44,
45,
46]. The used measurement data and the steps of identification are detailed in
Section 2, where the motor parameters (armature resistance and inductance, motor constant, moment of inertia, viscous friction constant) are identified directly from measurements based on the method shown in [
20,
30,
31,
34,
39,
47,
48,
49]. It will be proved that the mathematical model of the studied DC motor is linear so linear system modeling, identification and linear control methods can be studied in a comprehensive way. It is supposed that the motor parameters are constant and do not vary with time or temperature.
Control design can be performed by using continuous-time model and discrete-time model [
11,
12,
13,
14]. First, the continuous-time model and controller design are presented, and then the discrete-time model and design are studied in
Section 2. Processing sensor data, calculating control signal, and driving the actuator to achieve desired system behavior are realized by the microcontroller Arduino UNO [
50]. Finally, a simple, beginner-friendly and cheap microcontroller environment has been built to study DC motor measurements, modeling, identification and control. The implementation details are shown in
Section 3.
The paper focuses on feedback control of the motor speed, torque control can not be performed by the realized test bench.
The built laboratory equipment is suitable for the comprehensive testing of small DC motors, for building and identifying the motor model, as well as for testing the designed controllers. The equipment and the summarized theoretical results can be used for educational purposes too. The aim of the paper is that the measurements with the presented test bench as well as the controller design results can be reproduced. The measurement setup can be used to test new controller algorithms, here only conventional linear techniques are presented in detail. The novelty of this review paper is the presentation, modeling, analysis, and control of a second-order linear and time-invariant system in a comprehensive way. The results based on a literature search can be applied to other second-order systems; moreover, the results can be reproduced.
Section 2 presents the realized test bench, the theoretical background of state space modeling and transfer function representation, PID controllers and state feedback design, equations of the observer as well as the Kalman filter. The results are presented in
Section 3, and
Section 4 is for discussion. Some important Arduino UNO codes are in the
Appendix A,
Appendix B and
Appendix C.
3. Results
3.1. Measuring Some Motor Characteristics
With the open loop arrangement (
Figure 3), the static, i.e., the steady-state conditions can be easily investigated. Some data are shown in
Table 1.
The Arduino UNO uses a PWM signal to adjust the input voltage. The PWM output is 8-bit, i.e., the PWM value can be an integer between 0 and 255, thus determining the duty cycle, i.e., the armature voltage driving the motor.
By exciting the motor with different PWM values (
, the first row of
Table 1), the steady-state input voltage
, the steady-state armature current
, the rotor speed
and the angular velocity
can be measured. The steady state is typically reached within 1 second.
First, the relationship between the integer PWM input value and the stationary motor state variables is examined. In this case, the amplifier circuit is understood to be in the same block as the motor, as highlighted by the dotted line in the block diagram in
Figure 3.
Second, the relationship between the input voltage measured in volts and the state variables in the stationary state is discussed. In this second case, the amplifier circuit is understood as a block with the microcontroller, as highlighted by the dashed line in
Figure 3.
In the former case, the input-output relationship is nonlinear, while in the latter case, it is linear. In the controller design, the linear approach is used, and this approach is more closely related to the state space description of the motor since its input is the physically interpretable armature voltage measured in volts.
Figure 10 shows one of the static characteristics of the motor, the relationship between the 8-bit PWM excitation signal and the rotor speed. It can be seen that this is nonlinear, and given by the following characteristic:
This means that the motor shaft will not rotate until the 8-bit PWM excitation reaches (rounded up to the integer value) 47. The small circle indicates the measurement results and the solid line indicates the approximate values according to (
55).
All the interpolations performed by linear parameter estimation technique called the least square method [
11,
12].
In
Figure 10, a possible linear approximation is also plotted with a dashed line, with the equation
, the slope of which is calculated from the last measured data. This will not be discussed further.
The same type of armature current-PWM excitation relationship is described by
The PWM value of the excitation is related to the voltage measured on the motor terminals by a volt-meter instrument as follows:
The relationship between the armature voltage of the motor measured in volts and the rotor speed is linear according to the measurements shown in
Figure 11. The linear approximation is given by
The small circle in
Figure 11 indicates the measurement results, solid line indicates the approximate values according to the above equations.
The armature current-armature voltage relationship can also be considered linear to a good approximation (see
Figure 12):
The characteristic above is considered linear, below that the larger deviation is due to the inaccuracy of the sensor, and linear behavior is assumed for the rest of the paper.
3.2. Identification of Motor Parameters
In the steady-state the derivatives vanish in (1)–(4), and the following equations can be obtained:
from which
K and
k can be expressed:
It can be seen that the constants K and k depend on the value of the resistance .
The block diagram of
Figure 6 can be split into two separate parts as shown in
Figure 13. The input of the electric part is the voltage
and the output is the current signal
. The current is the input of the mechanical part, the output of which is the angular velocity
. Thus, if the input-output time functions of interest are available from measurements, the unknown coefficients in the blocks can be determined very accurately after a good choice of armature resistance. The inductance of the armature branch
and the moment of inertia of the mechanical part
J can be identified independently. The identification is, therefore, carried out in the following order:
Using the Matlab R2015a function, the motor parameters can be determined using an iterative procedure based on the golden section method as follows:
- (1)
Initialization of on the interval according to the rules of the golden section method;
- (2)
K and
k are defined by (
61) as a function of the resistance
, averaged over the measured stationary results (only the values between
and
in
Table 1 are used);
- (3)
Determine the value of the inductance
using the function
and the differential equation of the electric block shown in
Figure 13;
- (4)
Determine the value of the moment of inertia
J using the function
and the differential equation of the mechanical block shown in
Figure 13;
- (5)
Modify according to the golden section method, and go back to step 2 until the algorithm converges.
In step 3 and in step 4, the following differential equations must be solved:
and
In the former case, the time function of the current signal, in the latter the time function of the angular velocity is obtained. The calculated time functions are compared with the measured results and an error is calculated. To conduct this, the motor is excited with a PWM signal of 250, for example, and the time functions of angular velocity and current in the transient are measured. Given the measured data, the inputs of the electric and mechanical block can be generated separately and the differential equation can be solved numerically using one of the Matlab R2015a functions.
The identification results are as follows:
Substituting the parameters obtained from the identification in SI units into the state space description (
6), the following model can be obtained:
Substituting the above-mentioned physical parameters into the relations (
15) and (
16), the following transfer functions are obtained:
For the above state space description, for comparison, the following transfer functions are calculated by the Matlab R2015a function
:
Another, simpler solution to identify the continuous-time transfer function of the second-order system is as follows.
The parameters in the transfer functions (
21) can be determined using the Matlab R2015a
function. The error to be minimized is the difference between the angular velocity and current response calculated using the searched transfer function and the measured time functions.
The simulated angular velocity and armature current are obtained as a solution of the following state space model:
where
and
are notional state variables and
y is the notional output. The output vector
gives the angular velocity, and
gives the armature current.
To conduct the identification, the motor is excited with a PWM signal of 250, for example, and the time functions of angular velocity and current in the transient are measured.
The identified parameters are as follows:
i.e., the transfer functions are as follows:
Figure 14 shows the results of the switch-on transients for different input voltage values. The measured time functions of motor speed and armature current are compared with the model results. For speed, the results are plotted for 100, 150, 200 and 250 8-bit PWM voltage values, for current only the results for 150 and 250 PWM excitations are shown for better visibility. It is clearly visible that the current signal is quite noisy.
The time functions for the 250 PWM value have been used for the identifications.
3.3. Design of Linear Controllers
3.3.1. PID Controllers
The block diagram of the closed-loop control system for speed control used in this study is shown in
Figure 15. The plant to be controlled is the DC motor, whose speed
is controlled, and the reference signal is
. The difference between the two is the error signal:
The controller is designed for the transfer function
, i.e., assuming a plant model with input of armature voltage in the unit of volt and with the output of angular velocity in rad/s. The error term must, therefore, be converted from RPM to rad/s, this is conducted by the
block. The input of the controller is, therefore, the angular velocity error
and the output is the voltage
in the unit of volt. The output of the microcontroller produces a voltage in units of PWM, and the
block converts the voltage signal of the control algorithm into a PWM value. To conduct this, the relation (
57) is rearranged:
and the result, of course, is rounded to the nearest integer.
The control algorithm also contains a lower and an upper limit below and towards which the control signal must not go. These PWM values are 50 and 250. The motor does not rotate below 50 PWM (50 is used instead of 43 in the context (
57)), and the maximum value would be 255, but it is set to 250 in the microcontroller program. These limits should be taken into account when designing and checking the operation of the controller.
Design of the Continuous-Time PID Controllers
The PID controllers can be designed using the method of designing for phase margin using the open loop system Bode diagram. To conduct this, the polynomial-per-polynomial transfer function of the plant is transformed into a multiplicative form using the time constant, i.e.,
The slow time constant is , and the fast one is , the system poles are and , with which and .
As an example, let us design controllers for phase margin
. As an illustration, the design of a P-controller using
Figure 16 is used. In a Matlab R2015a environment, this can be easily conducted with the function
. For this:
- (1)
Plot the Bode diagram of the transfer function
of the open loop with unit gain, i.e., let
(
,
, and
, respectively), as plotted in
Figure 16;
- (2)
find the point (which here means the point ) on the phase diagram, and read off the cut-off frequency (in the example = 23.8 at , of course, the function can be used to obtain a more precise value, the error is due to the readout given by the graphical display);
- (3)
read off the value of the amplitude characteristic in decibel units at the cut-off frequency (here );
- (4)
determine the controller gain:
i.e.,
, which is a ratio without unit, since the
function represents
in decibels according to the relationship of
.
Figure 16.
Design of P controller for phase margin .
Figure 16.
Design of P controller for phase margin .
The design can be conducted without plotting the Bode diagram directly, but then a nonlinear system of equations must be solved:
This system of equations can be solved efficiently by calling the function. The two unknowns associated with the two equations are the controller gain and the cut-off frequency .
The step responses of the designed closed-loop control systems are compared in
Figure 17, and some characteristic data are summarized in
Table 2. Here,
is the cut-off frequency in units of rad/s,
K is the controller gain,
is the maximum value of the step response, and
is the steady-state value of the step response,
is the overshoot,
is the overcontrol, and finally
is the steady-state value of the control signal.
Table 2 shows that the higher the value of
, the faster the control loop is, as can be seen in
Figure 17, and that increasing
n further increases the controller speed. Also, the higher the value of the loop gain, the faster the controller. Further increasing
K will speed up the control loop. However, the acceleration leads to oscillatory behavior, as can be clearly seen in the simulation results, and in fact, large gains can make the closed-loop system unstable. However, fast control is possible with large control signals, as can be seen from the large overcontrol values
. A trade-off between the two must be found, i.e., to achieve the fastest control possible, but without saturating the actuating device. From the steady-state value
it is clear that a controller including an integrator allows accurate operation for the step reference signal. Overshooting occurs in all cases, which can be reduced by increasing the phase margin, reducing the gain, or reducing
n. This of course makes the control slower.
The closed loop system behavior is not very accurate when applying only a P-controller. It can be stated that the plant response can be accelerated by a PD block, the steady-state accuracy can be improved by a PI block, while PID altogether results in a fast and accurate control loop.
Discrete-Time Realization of the Continuous-Time PID Controllers
The sampled realization of the above-mentioned continuous-time PID controllers can be conducted by the step response equivalent transformation or by the unconditionally stable backward differential scheme, the right-hand-side rectangle rule, and the Tustin formula. The sampling period time is denoted by , i.e., the frequency of the sampling provided by the microcontroller is .
The constant gain of the discrete-time P controller is of course the same as the gain of the continuous-time controller.
By using
in the transfer function of the PI controller,
can be written. After a short transformation of
, the following difference equation can be obtained to obtain the discrete-time control signal:
Using the Tustin formula
results in:
and the step response equivalent transformation gives the difference equation of
In each of the three specifications, the
k-th value of the control signal
can be computed iteratively by the
k-th value of the error signal
and the
-th value of the error signal and the control signal. The implementing program is, therefore, the same in all three cases, but each value must be multiplied by a different weight. For a possible Arduino code, see
Appendix A,
Appendix B and
Appendix C.
The PI controller output signal can be approximated by
which results in the difference equation:
The control signal by the PD controller can be calculated by
when applying the approximation
. The Tustin formula
results in
and finally, the step response equivalent is as follows
where
.
Also in these specifications, the k-th value of can be computed iteratively by the k-th value of the error signal and the -th value of the error signal and the control signal.
The PD controller output signal can be approximated by
which results in the difference equation:
The approximate formulae of the PI-PD controller used are much longer, these are not detailed here, see the result in the code (
Appendix A).
Analysis of the Continuous-Time PID Controllers
The following reference signal contains three jump-like signal variations and one linearly varying segment, which allows us to study the behavior of closed-loop control systems:
The reference signal tracking of the P controller with phase margins
and
are shown in
Figure 18. The measured signal (green line) is noisy, so it is easily recognizable next to the simulated noiseless curves (red curve). The reference signal is the blue line.
The measured and simulated results show excellent agreement. The gain of the controller is for the larger phase margin and for the smaller one, i.e., the loop gain is and , respectively. From this, the static error can be computed according to , which is and , respectively. The measured and calculated static errors are equal to three decimals. It can be clearly seen that as the loop gain is increased, i.e., the phase margin is decreased, the overshoot in the transient is increased. The overshoot can be reduced by reducing the loop gain, but then the static error increases. It can be clearly seen that static error and overshoot reduction are conflicting demands. In the linearly decreasing section, the two curves are not parallel, and the error increases beyond all limits, since the type number of the control loop is , although the error appears to decrease (over the time interval considered) as the loop gain increases. It can be concluded that the problem cannot be solved satisfactorily with a purely proportional controller.
The reference tracking of the PI controller at
is shown in
Figure 19, where the reference, measured and simulated signals are the blue, green and red lines, respectively. Here, the measured and simulated results show excellent agreement. In transient, there is a small overshoot which can be reduced by decreasing the gain
, i.e., by increasing the phase margin, in this problem the overshoot at
phase margin practically disappears (then
). In the stationary state, the error is zero, since the integrating term increases the type number to
, and the speed follows the reference with a constant error in the linearly decreasing phase. It can be said that the PI controller is a good choice to solve this problem.
The reference tracking of the PD controller at
is shown in
Figure 20, with good agreement between the measured and simulated results. Again, reference, measured and simulated signals are the blue, green and red lines, respectively. The steady-state behavior of the control loop is inherently the same as that of the P-controller. The system cannot be accelerated significantly due to the saturation of the feedback loop, the feedback signal of the designed controller is sometimes many times higher than the upper limit of the PWM excitation signal 250, which means that acceleration does not occur in the real system. This is well observed for the time step jumps
and
. Here, the simulated speed has an overshoot, while the measured speed is without overshoot and the run-up is below the theoretical result. The effect of the differentiating branch in the controller causes the control signal to respond to the change in the error signal over a wide range with an abrupt, unpreferred change jerking the amplifier input. The PD controller is not recommended for this application for the above reasons.
The result of the PI-PD controller is not discussed separately because it is very similar to the result of the PI controller.
To set the sampling period
, the following rule of thumb can be used:
where the maximum value of the phase decay
is set to
. The sampling period time is
,
,
,
and
for P, PI, PD, PI-PD (
), and PI-PD (
) controllers according to the cut-off frequency data of
Table 2, respectively. By simply running the microcontroller’s
function, the resulting sampling period time for this implementation is on average around 30 ms, which corresponds to a sampling frequency of roughly 30 Hz, and is larger than the values given by the rule of thumb. However, it can be stated that the controllers perform satisfactorily, very close to the theoretical results. The largest difference in the calculated and measured transient was observed for the PD controller.
Design of the Discrete-Time PID Controllers
When designing a discrete-time PID controller, the first step is to transform the continuous-time transfer function of the plant into a step response equivalent form, where the sampling period
is predefined. The discrete-time transfer function of a DC motor is generally as follows:
where
M is a constant, and the discrete-time model has one zero
and two poles
and
. These of course depend on the sampling period. For the transformation, the Matlab R2015a function
is used. As an example, the transfer function at 50 Hz and 100 Hz is as follows:
The poles of a discrete-time system can be mapped from the poles of the continuous-time system according to the relation .
The design is conducted on a phase margin, in a similar way to the design of continuous-time controllers, by solving the following system of nonlinear equations:
The system of equations is solved by calling the Matlab R2015a function
. The step response of the designed closed-loop control systems are compared in
Figure 21, and some characteristic data are summarized in
Table 3. The nature of the step responses is of course the same as the results obtained for the continuous-time design (see
Figure 17).
By reducing the sampling period time, the results of the discrete-time model converge to the results of the continuous-time model, while the value of the control signal increases at the beginning of the transients.
The result of the controller design is a difference equation, which can be derived, for example, for the PI controller as follows. Start from the transfer function of the controller:
from which, after cross multiplication, the following equation can be written:
to which the following difference equation is given by the shift operator of the z-transform:
This equation gives the algorithm of the controller.
The PD controller can be implemented in a similar way as above:
and the algorithm of the PID controller is as follows:
Thus, the
k-th value of the control signal is the weighted sum of the
-th value of the control signal, the
k-th,
-th and
-th values of the error signal. The controller program is very easy to implement using a general form of
which results in the difference equation:
The included coefficients are summarized in
Table 4 and in
Table 5 at 50 Hz and 100 Hz sampling frequencies, respectively.
The results for discrete-time PID controllers are not discussed separately but are very similar to those for continuous-time PID controllers. The implemented Aruino code of
is presented in
Appendix B for further use.
3.3.2. State Feedback Controllers
Observer Design to Measure the Current Signal
The discrete-time state-space model of the continuous-time system is obtained by the Matlab R2015a function
. The sampling period is defined to
(
), and
The eigenvalues of the system matrix, i.e., the poles of the system, are and .
The vector
is determined by Ackermann’s formula, with the observer’s poles at
. The Matlab R2015a function
gives the result of
The approximation of the armature current and speed for a stepped excitation is shown in
Figure 22. The measured current signal is quite noisy in this range, but the currents calculated with the continuous-time observer and the discrete-time observer are close to each other. The measured and observed speeds are in perfect agreement.
Kalman Filter to Estimate the Current Signal
To determine the covariance matrix of the Kalman filter
and the covariance
, the measurement result shown in
Figure 23 is used when the motor is excited with a constant PWM signal of 150.
The mean values calculated from the
sample are
,
, and the covariances are as follows:
The gain of the Kalman filter
can be determined by the Matlab R2015a function
, which numerically solves the Riccati Equation (
44). Then,
and
can be calculated:
The estimated speed signal and the estimated current signal obtained by the Kalman filter have been used in the control loop.
LQ-Based State Feedback Design
After some trials, the following choice leads to a very similar result to the second case obtained by Ackermann’s formula:
Controller gains are obtained by the solution of (
52) and (
53).
A possible discrete-time state feedback controller implementation can be studied in
Appendix C for further use.
4. Discussion
The DC motor analysis with real laboratory tests showed the well-known theoretical result that the DC motor can be modeled as a linear plant in the control systems. From the steady-state and switch-on measurements, the linear state space model as well as the transfer function model have been identified, and it is supposed that the model is second order. Measurement results and simulated curves show a very good agreement.
Continuous-time PID controllers have been designed via the well-known phase margin method, and the discretized form of the controllers has been implemented in the Arduino UNO microcontroller. The discrete-time model-based PID controllers are also designed and realized. The two approaches result in the same control signal as well as the same output signal. The continuous-time model is a little bit easier to understand, and the results of the discrete-time model proved that the continuous-time controller can be used efficiently; however, the discrete-time model is closer to the theory of discrete-time controller design. Moreover, discrete-time modeling can be implemented in microcontrollers. More complicated problems should be worked out in the frame of the discrete-time theory because the sampling time can be fixed at the very first step of the design.
The noisy current signal is efficiently measured by the state observer as well as by the Kalman filter. It is highlighted that the Kalman filter did not result in a much better noise reduction, meaning that the Kalman filter parameters should be adjusted as a future task as well as the noise model parameters. Practically, in this application the deterministic state observer and the Kalman filter gave the same measurement results.
State feedback controller design has been realized and the pole placement has been studied comprehensively. LQ optimal controller was also studied. The design of the parameters, i.e., the matrix
and the parameter
R should be improved, to reach a predefined closed loop system output and control signal [
55].
There are some other linear controllers that can be realized, e.g., the two degrees of freedom controller, dead-beat controller, optimal controller with conditions on the control signal, model predictive controller and so forth. Linear control suffers from obvious limitations in terms of lack of disturbance handling and modeling uncertainties. The effect of uncertain model parameters and disturbances can be decreased by the integral term of the control loops mentioned in the paper; however, uncertainty and disturbance can be handled efficiently by robust control methods [
56,
57]. This paper has not worked on these questions, these can be the focus of fruitful future tasks. The paper mentioned only a full-order observer to estimate the state vector elements; however, reduced-order state estimation can be applied. This can be a future task as well.
The test bench is easy to realize, the motor, the sensors and the microcontroller are very easy to build and assemble, and it can be a useful tool for engineering students in undergraduate systems and control lectures and laboratories. This is why the Arduino codes are inserted for further studies.
There are, of course, many other microcontroller-based platforms for solving the problem presented in this review. The Arduino UNO is a cheap and simple solution that is also very useful in undergraduate control engineering education. For more complex problems that require more computing power or special tasks, other types of hardware should be used.