Next Article in Journal
Compressing and Recovering Short-Range MEMS-Based LiDAR Point Clouds Based on Adaptive Clustered Compressive Sensing and Application to 3D Rock Fragment Surface Point Clouds
Previous Article in Journal
The Improvement of Density Peaks Clustering Algorithm and Its Application to Point Cloud Segmentation of LiDAR
Previous Article in Special Issue
A W-Shaped Self-Supervised Computational Ghost Imaging Restoration Method for Occluded Targets
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Ultrasonic Obstacle Avoidance and Full-Speed-Range Hybrid Control for Intelligent Garages

1
School of Measurement-Control Technology and Communications Engineering, Harbin University of Science and Technology, Harbin 150080, China
2
The Higher Educational Key Laboratory for Measuring & Control Technology and Instrumentation of Heilongjiang Province, Harbin University of Science and Technology, Harbin 150080, China
*
Author to whom correspondence should be addressed.
Sensors 2024, 24(17), 5694; https://doi.org/10.3390/s24175694 (registering DOI)
Submission received: 24 June 2024 / Revised: 23 August 2024 / Accepted: 28 August 2024 / Published: 1 September 2024
(This article belongs to the Special Issue Advanced Sensing and Measurement Control Applications)

Abstract

:
In the current study, which focuses on the operational safety problem in intelligent three-dimensional garages, an obstacle avoidance measurement and control scheme for the AGV parking robot is proposed. Under the premise of high-precision distance detection using Kalman filtering, a mathematical model of a brushless DC (BLDC) motor with full-speed range hybrid control is established. MATLAB/Simulink (R2022a) is used to build the control model, which has dual closed-loop vector-controlled motors in the low- to medium-speed range, with photoelectric encoders for speed feedback. The simulation results show that, at lower to medium speeds, the maximum overshoot of the output response curve is 1.5%, and the response time is 0.01 s. However, at higher speeds, there is significant jitter in the speed output waveform. Therefore, the speed feedback is switched to a sliding mode observer (SMO) instead of the original speed sensor at high speeds. Experiments show that, based on the SMO, the problem of speed waveform jitter at high motor speeds can be significantly improved, and the BLDC motor system has strong robustness. The above shows that the motor speed under the full-speed range hybrid control system can meet the AGV control and safety requirements.

1. Introduction

With the continuous improvements in citizens’ quality of life, the number of car owners in China is also rising. Taking the capital city of Beijing as an example, compared to the same period last year, the number of motor vehicles in the city has increased by 462,000, and it has maintained a continuous growth trend. On the other hand, due to the rigid constraints of land resources and the lag in parking space construction standards, the supply of parking spaces in many cities in China is seriously insufficient.
The state has introduced a series of policies to solve the parking problem in a timely manner. However, the results are still slightly insufficient compared with the parking difficulties faced in our country. With the development of computer and automation technology, the intelligent garage systems are gradually emerging. As the key to the achievement of intelligent management of a three-dimensional garage, the measurement and control mode of AGV parking robots directly affects the efficiency, reliability, and safety of vehicle access. This has become a research hotspot in the field. According to public data released by various companies in the market, the use of AGVs can increase the utilization rate of a parking area by at least 40%, so the development of parking robots is very consistent with the national expectations for the construction of smart cities, and there are broad application prospects [1].
The purpose of this paper is to explore the obstacle avoidance system of AGVs. Under the condition of achieving the required accuracy for ultrasonic distance measurement of obstacles, speed control methods for brushless DC (BLDC) motors are studied. That is, during the movement of the AGV along a given trajectory, the motor control system decelerates and stops accordingly when encountering obstacles, and the local path optimization system (A* algorithm) intervenes to re-plan the trajectory or sound an alarm and stop the movement of the AGV [2]. This system is based on accurate control of the speed of the BLDC motor; after the BLDC motor converts electrical energy into mechanical energy, the AGV starts to run. The dual closed-loop control method for speed and torque in AGV driving is the research object of this paper. In order to meet the actual operational requirements of the AGV, under the premise of using a vector control algorithm to drive the motor, a photoelectric encoder is used to detect the speed in the low- to medium-speed range and a sliding mode observer is used in the high-speed stage, so as to meet the speed requirements in the full speed range. Based on the precise acquisition of the BLDC motor’s speed, the accurate displacement information of the vehicle is obtained, improving the accuracy of the vehicle’s stopping position and ensuring the safety of the AGV.
At present, the motor models of intelligent garage drive systems are different. This article selects from the following aspects.
  • Cost efficiency: in terms of cost, the price of the excitation synchronous motor and servo motor is higher, so a BLDC motor is selected.
  • Dual closed-loop control: in the case of a dual closed-loop (current outer loop and current inner loop control) control method, a BLDC motor can achieve excellent speed and torque response curves, avoiding the complex three-closed-loop control method [3].
  • Algorithm complexity: the algorithm complexity of the SMO is lower than that of a Kalman filter algorithm [4] and neural network control [5].
  • Robustness and Simplicity: it is more robust than the Luenberger observer [6], and the BLDC motor debugging process is simple.
  • Faster Response and Reduced Chattering: the BLDC motors have faster response speeds and lower chattering than fuzzy control [7] and PI control.
After careful consideration [8], a BLDC motor was selected as the drive system in this paper.

2. AGV Ranging System

2.1. Ranging with Ultrasound

An HC-SR04 ultrasonic sensor is selected for ranging; the ultrasonic ranging method adopts the transceiver separation method, and the basic principle of ultrasonic ranging is the time difference ranging method [9]. As shown in Figure 1, the trig pin sends a pulse to indicate that the sensor is starting to work, and the wait time for the echo pin to outputs a high-level signal (the reverberation time in Figure 1) from the HC-SR04 sensor is the time difference t. The microcontroller captures this time difference, and the distance to the obstacle is calculated based on the speed of sound. S is the distance from the ultrasonic transmitter to the obstacle, and the distance calculation formula is
S = v · t 2
where v is the propagation velocity of ultrasonic waves in air.
Since the speed of sound-wave propagation in air is related to temperature, temperature compensation is required under high accuracy requirements. After adding temperature compensation, the relationship between the speed of sound-wave propagation in air and temperature [9] is as follows:
v = 331.4 + 0.607 T
where T is the ambient temperature at the time of measurement.

2.2. Kalman Filter Algorithm

The Kalman filter algorithm [10] first uses the linear system state equation, then, through the system input and output observation data, finally carries on the optimal estimation of the system state. Kalman filtering is widely used in various fields, especially in distance detection, and its ability to correct data is particularly significant [11]. For research on indoor ultrasonic positioning technology, the modal optimization Kalman filter algorithm is used. The algorithm optimizes the distance measured by the ultrasonic probe [12], so that the correction value is very close to the actual value, and after 50 recursions, the error is controlled within the range of ±1 cm. Therefore, the feasibility of the Kalman filter algorithm can be verified.
When laser radar ranging is applied in the fields of autonomous driving and aerospace, the ability of Kalman filter technology to correct data is particularly significant. For example, in the real-time tracking problem of missile trajectories, firstly, the accurate distance and velocity data provided by radar are used. Then, the interactive multi-model Kalman filter algorithm [13] is used to optimize the battle. Finally, through simulation experiments, the actual trajectory of the missile basically coincides with the filtered trajectory. Therefore, under the premise of considering the applicability of the three-dimensional garage, the Kalman filter algorithm is added to the measurement process to reduce the measurement error.
Kalman filter is a recursive estimation algorithm. Under the premise of minimum mean square error as the best criterion for estimation, the optimal estimation is sought over time. The basic idea is that on the basis of constructing the state space model of output and noise, the estimated value and the measured value are combined. The predicted value-measured and value-corrected value is continuously repeated, and the random error and noise of the system are eliminated according to the measured value of the system.
The output ultrasonic observation model of the ultrasonic sensor is
x 1 . k x 2 . k = 1     1 0     1 x 1 . k 1 x 2 . k 1 + w 1 . k 1 w 2 . k 1   z 1 . k z 2 . k = 1     0 0     1 x 1 . k x 2 . k + v 1 . k 1 v 2 . k 1            
where x1.k x2.k are the ultrasonic arrival distance and the acoustic wave propagation velocity under the prediction model, respectively; z1.k z2.k are the arrival distance and velocity of acoustic wave in the actual propagation model of ultrasonic wave; w1.k−1 w2.k−1 is the measurement process noise; v1.k−1 v2.k−1 is the measurement noise.
The noise w1.k−1 w2.k−1 in the measurement process is affected by the temperature and humidity and the flatness of the measured object surface. The sampling rate of the single-chip microcomputer mainly determines the measurement noise v1.k−1 v2.k−1. In the calculation process, the two kinds of noise can be processed according to the normal distribution [14], and the variances are set to Q and R, respectively.

2.3. Preprocessing Flow of Kalman Filtering

Kalman filtering is a linear system state equation. The Kalman filtering process of the output of the ultrasonic sensor is as follows [11]:
  • The optimal estimate of the previous moment is used as input for the prediction parameter of the current distance;
  • The variance of the prediction is the sum of the variance of the optimal estimate at the previous moment and the process variance. According to the influence of sensor error, car running resistance, temperature, and atmospheric pressure, this paper takes the process variance Q = 0.01;
  • Considering the velocity as constant, the system can be transformed into a one-dimensional Kalman filter to calculate the Kalman gain;
  • According to the measured value at the current moment, the prediction at the previous moment is corrected to obtain the optimal estimation after correction, and the variance of the final estimated value is calculated;
  • As the sampling process progresses, the process of (2)~(4) is continuously repeated.
The measurement variance reflects the measurement accuracy of the sensor. According to the sensor parameter data, v has been processed according to the normal distribution [12], so the R-value is the variance of v. The variance of v is calculated to be 0.096 by the initial measurement result, so R takes 0.1. The estimated variance of the initial value depends on the accuracy of the initial value setting. In this paper, p = 1.0 is taken.
A horizontal obstacle is placed in the measurement range (2–450 cm) of the sensor HC-SR04, and then the ranging experiment is carried out. As shown in Figure 2, it is the absolute error of the unpreprocessed data and the Kalman filter data with the actual value, respectively, indicating that the average ranging error is reduced by 32% under the filtering effect.
Table 1 shows the error comparison after filtering under the PauTa criterion, indicating that the random interference is effectively suppressed, which meets the accuracy requirements of AGV ranging.
According to the test and data processing analysis, the results show that the average error of the measurement results after Kalman filtering is less than 0.17 cm, which is 39% lower than 0.28 cm before filtering, and the fluctuation of the sampling results after filtering is minor.

3. The Motor Control Algorithm

3.1. Establishment of Motor Model

According to the current mainstream AGV design companies, such as Hikvision, KUKA, Dematic, etc., the total driving force [15] required for AGV driving Fz is 1562 N. The parameters required for designing AGV are as follows: the average driving speed of AGV Vx is 0.58 m/s, the diameter of AGV driving wheel D is 18 cm, the number of driving motors n is 10, the reduction ratio of motor reducer i is 20, and the transmission efficiency of the motor output shaft from the reducer to the driving wheel is 0.73. According to these parameters, the calculation formulas of the rated power P, the rated torque T, and the rated speed N of the motor are Equations (4), (5), and (6), respectively.
P = F z V x n η
T = F R n i η
where R is the radius of the driving wheel.
                              N = 60 V x i π D
The specific parameter requirements are calculated as shown in Table 2.
Under the premise of meeting the requirements of information parameters in Table 2, according to the driving ability required by the distance measurement accuracy of the sensor in Table 1, this paper chooses the Z55BLD300-36GU DC brushless motor.
For the realization of the motor control algorithm, according to the motor parameter characteristic hypothesis and model analysis of BLDC in reference [16], the simplified mathematical equation of the motor is established in this paper. The simplified equivalent circuit diagram of BLDC is shown in Figure 3. Through the analysis and prediction of the running state of the motor, different control principles can be designed, and the corresponding photoelectric sensor and sliding mode controller are used to obtain the speed feedback, respectively, so as to design the appropriate control strategy to achieve the desired speed regulation effect. The voltage equation of BLDC is as follows:
U a U b U c = R       0       0 0       R       0 0       0       R I a I b I c + B d d t I a I b I c + E a E b E c
where R L and M are phase resistance, phase inductance, and mutual inductance, respectively; B is the matrix L M   0 0 0 L M   0 0 0 L M   ; Ux Ix and Ex are the three-phase voltage, phase current, and opposite electromotive force, respectively; x takes a, b, and c to represent the three-phase windings, respectively; UN is the star connected neutral voltage.

3.2. Speed Detection Circuit

In the low- and medium-speed-range BLDC control system, the motor output speed must be detected, and the measured speed is fed back to the PI controller to complete the speed closed-loop control. Considering the advantages of photoelectric sensors, such as their high accuracy and resolution, strong anti-interference ability, non-contact measurement, and high accuracy of displacement detection, the photoelectric encoder is selected as the BLDC output speed measuring device.
The structure principle of the photoelectric encoder is shown in Figure 4, and the working principle is as follows:
  • The prisms convert the scattered light emitted by light-emitting diodes into parallel light, and fixed gratings ensure that this light enters the photosensitive tube. The grating disk rotates with the BLDC, and the photosensitive tube completes the optical–electrical signal conversion, and then outputs three sets of pulse square waves. They are AB two-phase square waves with a duty cycle of 50% and a phase difference of 90°, as well as Z-phase zero pulses. (One pulse is output per revolution).
  • Enter the single chip microcomputer through the interface circuit in Figure 5, then the single chip microcomputer captures the input pulse according to the interrupt service program, finally uses the frequency doubling technology (the rising edge and the falling edge of the AB two-phase square wave are both considered as pulses) to obtain a 4-fold frequency doubling pulse.
  • The BLDC speed is calculated using the periodic measurement method. This method obtains a high-frequency pulse with a known frequency and counts it. The calculation formula of the speed n is
    n = 1 C T E = F 0 C M 1
    where TE is the counting time, which is determined by the interval time between two adjacent pulses of the encoder captured by the single-chip microcomputer; M1 is the corresponding number of counts; C is the total number of pulses in a single turn of the encoder; and F0 is the frequency of the pulses.
The interface circuit diagram of the photoelectric encoder is shown in Figure 5. HCPL060L is a photoelectric isolation device. The pulse signal generated by the photoelectric encoder enters the interface circuit and is then electrically isolated by HCPL060L. The isolated signal is processed after being captured by the timer of the single-chip microcomputer. This design can effectively prevent the influence of noise and interference in the encoder signal on STM32 and can improve the stability and reliability of the system.
When HCPL060L is in an extreme electromagnetic environment, its ability to resist unstable light interference worsens [17], which affects the accuracy of speed measurement and, ultimately, reduces the control accuracy and dynamic performance of the motor.

3.3. Vector Control Algorithm Rotation

BLDC is a complex system with multivariable, decoupling and nonlinear characteristics. The speed of BLDC cannot be effectively controlled within the required range by using ordinary inductive control (six-phase commutation method). Therefore, this paper adopts the FOC control algorithm.
The FOC algorithm, also known as Field-Oriented Control [18], is an advanced algorithm for AC motor control. The core idea is to transform the control problem of the AC motor into the control problem of the DC motor, so as to realize the efficient and accurate control of the AC motor.
FOC aims to reduce the torque ripple and noise of the motor by accurately controlling the size and direction of the magnetic field, and can quickly respond to speed, rotor position, and torque commands, thereby achieving accurate control of torque and speed. As shown in Figure 6, the realization of the FOC algorithm is based on the Clark and Park coordinate transformation [18]. The FOC algorithm converts the three-phase stationary coordinate system (abc) into a two-phase rotating coordinate system (dq), which simplifies the control model and serves as the input to the PI controller. The Clark transform equation in the study is
I α I β = 3 2   1   1 2   1 2 0       3   2   3 2   I a I b I c
where αβ is the two-phase stationary coordinate system.
The Park transformation formula is
I d I q = c o s θ         s i n θ s i n θ         c o s θ   I α I β
where θ is the current rotor position.

3.4. SVPWM Algorithm

The SVPWM algorithm [19] controls the switching state of the three-phase inverter and then generates a voltage or current output that is close to the ideal sinusoidal waveform. The SVPWM algorithm considers the inverter and the motor as a whole. By controlling the switching sequence of the inverter, the output voltage space vector achieves an ideal circular trajectory.
The seven-segment SVPWM algorithm used in this paper and the generation method of the space voltage vector U in each sector are as follows: U consists of two zero vectors (U0, U7) and two adjacent non-zero vectors (U1~U6). The non-zero vector selected by the U in each sector of the synthesis corresponds to the state of the inverter MOS tube, as shown in Figure 7.
The generation of U first obtains each basic vector (U0~U7) through the switching state of the MOS tube and determines the sector where the current U is located according to the two adjacent non-zero vectors. Finally, according to the action time transformation of the above two pairs of adjacent vectors, the synthetic space voltage vector U in each direction is obtained, thereby driving the motor rotor to rotate smoothly.
The zero vector and the non-zero vector are combined to form the corresponding PWM waveform. Finally, the capture register (CCR) values corresponding to the three timers are obtained. According to the state combination of the power switch in the inverter circuit and the adjustment of its switching time, a space voltage vector with a circular trajectory is generated so that a uniform circular rotating magnetic field is generated in the AC motor.
In the vector control system, according to the selected control strategy, through the appropriate coordinate transformation, the components of the voltage space vector in the two-phase stationary coordinate system are obtained. Finally, through the SVPWM control, the specific algorithm steps are as follows:
1. According to the Uα and Uβ obtained by the anti-Park transformation, the variable U1, U2, and U3 are defined. The calculation formulas of the three are as follows:
U 1 = U β , U 2 = 3 2 U α 1 2 U β , U 3 = 3 2 U α 1 2 U β .
2. The sector number of the space voltage vector (IVI in Figure 7 ) is determined and calculated by reference voltage components (U1, U2, and U3).
N = s i g n U 1 + 2 s i g n U 2 + 4 s i g n U 3
where the sign is the function, if Ux > 0, the function value is 1; if Ux < 0, the function value is 0.
And the corresponding sector is calculated based on Figure 7, sector location N.
3. Define the variables X, Y, and Z. According to the sector number obtained in Table 3, the action time of the corresponding basic space vector is determined.
X = 3 T s U β U d c Y = 3 T s U d c 3 2 U α + 1 2 U β Z = 3 T s U d c 3 2 U α + 1 2 U β
where Ts is the timer PWM period and Udc is the BLDC bus voltage.
According to the obtained X, Y, and Z, the values of the two non-zero vectors (rotated counterclockwise) corresponding to each sector are obtained.
When determining the output constraints for SVPWM modulation, in the process of software simulation, rounding is used in order to simplify the operation. Therefore, it is necessary to compare the working time Ta, Tb and the modulation period Ts. If it does not meet the actual conditions, it needs to be processed.
T a = T a T a + T b T s T b = T b T a + T b T s
4. The PWM generation of a single-chip microcomputer adopts the center alignment mode. In this mode, the single-chip microcomputer can generate the symmetrical PWM waveform, and an accurate synthetic magnetic field vector can be generated by the SVPWM algorithm. Therefore, the setting of the CCR value in the timer should be determined first.
First, the following three variables are defined: T1, T2, and T3. According to the values of Ta and Tb in each sector, as shown in Table 4, these three variables can be obtained.
T 1 = ( T s T a T b ) 4   T 2 = T 1 + T a 2 T 3 = T 2 + T b 2
The corresponding relationship between the three-phase voltage switching points CCR1, CCR2, and CCR3 and each sector is shown in Table 5.
5. On the basis of the principle of the minimum number of MOS tube-switching operations, the order and time of each sector voltage vector are determined. Finally, the value of CCR in the timer setting of the single chip microcomputer is determined according to Table 5.
Taking the first sector as an example, the three-phase modulation wave generated by it is shown in Figure 8 in the period Ts. The order of appearance of the voltage vectors in the figure is 0→4→6→7→7→6→4→0.
In summary, the SVPWM algorithm process includes the sector judgment of the reference voltage vector, the calculation of the non-zero vector and the zero vector action time of each sector, and the determination of the switching point of each sector vector. Then, comparing the corresponding frequency triangular carrier signal with each sector vector switching point, the six PWM pulse signals required by the three-phase inverter are finally generated.

3.5. Sliding Mode Observer

For the output-speed feedback of the photoelectric encoder under the vector control algorithm, it is not sufficient to meet the AGV speed requirements. In order to improve the response speed of the drive system and improve the accuracy of the position feedback system, on the basis of the vector control strategy, the sliding mode observer is used in the high-speed stage of BLDC to strengthen the control of the output speed of the motor.
SMO is an advanced algorithm [20] for sensorless vector control of motors. The algorithm is mainly used to estimate the rotor position and speed of the motor in real time, so as to realize the accurate control of the motor. SMO is an observer based on the theory of sliding mode control. The core concept of the SMO is to design a sliding surface so that the system state can slide along the sliding surface after reaching the sliding surface, and finally realize the observation of the position and speed of the rotor.
1. The first step is to design the SMO and select a suitable control function to reduce the output chattering problem. The mathematical model of the SMO is established based on the motor voltage equation in the stationary coordinate system, and the voltage equation in the stationary coordinate system obtained by Clark transformation of (7) is
U α U β = R + p L d                 0 0                 R + p L q I α I β + E α E β
The counter electromotive force contains the motor speed information, and the voltage equation becomes the current equation in the same coordinate system as follows:
d d t I α d d t I β = R L d 0 0 R L d I α I β + 1 L d U α U β 1 L d E α E β
2. To obtain an estimate of the counter electromotive force, a sliding mode observer is designed according to the observation current equation in the BLDC stationary coordinate system:
d d t I α ^ d d t I β ^ = A I α ^ I β ^ + 1 L d U α U β 1 L d v α v β
where I α ^   I β ^ are the current observations in the stationary coordinate system; vα vβ are the control inputs to the observer, which can be expressed as follows:
v α v β = k · s g n I α ^ I α k · s g n I β ^ I β
where k is the slip film gain and sgn is the sign function [21].
The appropriate k value can make the observation current converge to the actual current more quickly and can reduce the jitter of the observation current and the SMO output speed after the stability, so as to improve the speed extraction accuracy.
3. In order to better reduce the chattering and remove other high-frequency noise in the system, a low-pass filter is added after the output vα vβ of the sliding mode observer, and its mathematical model in the frequency domain is
H j ω = ω c ω c + j ω e
where ω c is the cutoff frequency and ω e is the is the identification speed.
4. The rotor position and speed are estimated by phase-locked loop (PLL). The PLL [22] algorithm is widely used in digital signal processing, especially in the fields of communication, power electronics, and motor control. Its main purpose is to track the input signal’s phase to extract its frequency and phase information. The equation for the PLL estimation of rotor speed is as follows:
ω ^ = E α ^ c o s θ ^ E β ^ s i n θ ^ k p + k i s
where E α ^   E β ^ is the observed value of the back electromotive force after the filter; k p is the proportional value of the PI controller, and k i is the integral value of the PI controller.
The estimated speed of the rotor extracted by the phase-locked loop needs to be output by the integrator, which is the rotor position estimation.

4. Simulation of Drive and Control System

4.1. Design of Low- and Medium-Speed-Range Control Systems

At low and medium speeds, the photoelectric encoder is used for dual closed-loop vector control, and the PI controller is used in the speed outer loop and the current inner loop. The rotation axis of the photoelectric encoder follows the rotation of the motor, and the mechanical angle of the motor output rotor is used as the input of the photoelectric encoder. Figure 4 shows that the photosensitive tube generates an ABZ three-phase pulse, and the current motor speed is calculated through Formula (8). And the output speed of the photoelectric encoder is passed through the low-pass filter, so that the high-frequency noise can be removed and the output speed chattering can be reduced and used as the feedback of the PI controller. The cut-off frequency of the low-pass filter is the output PWM frequency of the SVPWM algorithm. The simulation model of the system is shown in Figure 9.

4.2. PI Parameters Tuning

The use of the critical ratio method, attenuation curve method, and other engineering rectification methods cannot adjust the PI parameters in time according to the external environment, which will affect the system’s regular operation. In this paper, the theoretical calculation setting method [23] is selected, so the calculation amount is reduced by the Laplace transform. The premise of Laplace transformation is a linear constant system, so the transfer function is constructed under the assumption of ignoring the coupling term in the current loop controller.
1. Calculate the transfer function of the BLDC in the dq axis coordinate system according to Equation (7).
u d = R i d + L d d i d d t u q = R i q + L q d i q d t
After the Laplace transform, the transfer function is
G d s = i d s u d s = 1 R + L d s G q s = i q s u q s = 1 R + L q s
2. Using the parallel PI controller, under the premise of ignoring the system delay link and filtering the feedback current, the open-loop transfer function of the motor current loop system shown in Figure 10 is
G o p e n s = i d s i d s * = k p + k i s 1 R + L d s
Simplify the current loop closed-loop transfer function to obtain
G c l o s e s = k p s + k i L d s 2 + k p + R s
Then create the following equation
k p = L d ω c k i = R ω c
where ω c is the current loop bandwidth, and related to the time constant τ of the motor, which can be substituted to simplify the closed-loop transfer function
G c l o s e s = ω c s + ω c
This is calculated using the following formula:
τ = m i n L d R , L q R ω c = 2 π τ
The poles of the open-loop transfer function are negative, so the k p   k i of the current loop can be obtained on the premise that the transfer function is stable.
3. The parameters of the speed-loop PI regulator are set by the following formula
K p = β J 1.5 p n ψ f K i = β K p                
where β is the expected bandwidth of the speed ring, which is taken as 50; J is the moment of inertia, Pn is the number of pole pairs; ψ f is the motor flux linkage.
4. PI parameters under dual closed-loop vector control can be obtained.
Substituting the Table 6 parameters into the PI controller in Figure 9.
5. For the coupling term shown above, through comparison in the simulation experiment, it can be seen that the coupling term is used as the error input of the current loop PI controller, and the current waveform output by the motor is better.

4.3. Construction of High-Speed Range Control System

In order to obtain a better speed output response curve, SMO is used to estimate the speed and position of the motor rotor at high speed, and the estimated value is used to replace the speed and position value detected by the photoelectric encoder in the original system. The sliding mode observer is a nonlinear observer. Compared with other state observers, it has excellent robustness based on high dynamic response capability [24]. SMO uses the sign function to replace the actual value of the deviation, which not only effectively copes with external interference, but also effectively improves the stability of the control system. Figure 11 shows the SMO simulation module [25].
The high-speed stage simulation build process is as follows:
1. Firstly, for the BLDC output three-phase current and voltage, the two-phase stationary coordinate system (αβ) is obtained by anti-Park transformation, and the differential of the actual value of the current is obtained by substituting this into Formula (17). Then, the actual value of the current in the two-phase stationary coordinate system can be obtained by integrating the differential value. Finally, according to Formula (18), the differential of the corresponding observation value is obtained.
2. To keep the observer state in the sliding mode plane I α ^ I α all the time, according to the sliding mode control law of Equation (19), the estimated value of the back electromotive force can be obtained, and the estimated value of the back electromotive force is filtered as the PLL input.
3. The PLL simulation module is built according to (21), and the output value is the rotor speed observation value. After the speed is integrated, it is the rotor position observation value.
The method of calculating each parameter in the simulation module is the experimental debugging method. Synovial gain K value is 200; the value of wc in the filter is 4000; in the PI controller of PLL, Kp = 43, Ki = 20,000.

5. Simulation Analysis

To verify the validity and reasonableness of the proposed method, according to the simulation model of Matlab/Simulink (R2022a), the parameters of the BLDC are set in the full speed range as follows: line resistance R = 0.4 Ω, line inductance Ld = Lq = 0.8 mH, moment of inertia J = 0.000021 kg·m2, flux linkage Ψ = 0.04457 Wb, and number of pole pairs p = 2.
In order to study the speed defect of photoelectric encoder detection, the photoelectric encoder is used to measure the speed. Under the premise of not exceeding the maximum speed set in Table 2, under the premise of not exceeding the maximum speed set in Table 2, BLDC operates at variable speed within the speed stages of 500, 600, 700, 900, 1100, 1200, and 1300 rad/min, respectively. The simulation results are shown in Figure 12.
The simulation results show that the output speed waveform of the motor is relatively stable in the low-speed operation stage. Still, there is an apparent jitter in the speed output waveform at high speed. Therefore, based on this defect, the SMO algorithm is added for speed feedback. In order to determine the switching threshold of the SMO algorithm, the BLDC uniform acceleration driving experiments can be conducted, and the simulation is carried out on the basis of two different algorithms. The simulation results are shown in Figure 13.
The simulation results in Figure 12 and Figure 13 show that there is no overshoot at the time of speed switching, and the robustness of the system is verified. And it can be explained that under the premise of the feedback speed of the photoelectric encoder, the AGV speed output is stable when driving at low speed. Figure 13 shows that when the BLDC speed exceeds 900 rad/min, the output waveform of the speed feedback of the encoder is seriously jittered. Still, on the basis of the SMO algorithm, the output waveform of the speed feedback is stable.
In order to accurately determine the threshold of SMO algorithm switching, this paper selects the initial speed of 890 rad/min, lets the speed increase in turn, and compares the feedback speed waveforms of the two control methods.
In order to further reflect the chattering of the velocity waveform and obtain the switching threshold more accurately, Table 7 shows the standard deviation of each velocity stage obtained by Bessel formula.
According to Figure 13, the threshold of the SMO algorithm switching is around 900 rad/min. According to the standard deviation values of Figure 14 and Table 7, the standard deviation of the photoelectric encoder speed feedback is larger than that of the SMO algorithm after the speed exceeds 920 rad/min, so the threshold is 920 rad/min. In order to further verify the effectiveness of the SMO algorithm in the high-speed range, the sliding mode observer is switched to the simulation control in the high-speed stage. Five high-speed ranges with noticeable differences and significant jitter are selected, respectively, and then the speed feedback waveforms of the SMO algorithm and photoelectric encoder are compared. The results are shown in Figure 15.
The simulation results in Figure 13 and Figure 15 show that the output speed waveform jitter phenomenon is significantly optimized in the high-speed range. Combined with the comparison results of 920–1300 rad/min range, the maximum chattering value can be reduced from 10.8 to 5.2 rad/min after the speed reaches a steady state. It can be concluded that the speed feedback value is more concentrated, closer to the real value, and more in line with the control requirements. Therefore, the output error is significantly reduced, and the system stability is improved, which is in line with the expected goal.
In vector control, the phase error is more important than the velocity error. The phase error is the radian difference between the actual rotor position and the rotor position measured by the photoelectric encoder, and also the radian difference between the actual rotor position and the rotor position estimated by SMO. In order to study the superiority of the SMO algorithm in the high-speed range, the rotor positions of the three cases are compared in the high-speed range of BLDC. The phase error is shown in Figure 16.
According to the observation angle of the motor in the high-speed range in Figure 16, it can be seen that there is a deviation between the rotor phase measured by the photoelectric encoder and the actual value, which will cause an increase in chattering and a decrease in control accuracy. However, there is no phase error under the SMO algorithm, which verifies the feasibility [26] of the SMO control strategy within the high-speed range.
Because the actual operation mode of AGV in the intelligent garage is more complex, in order to verify the performance of the full-speed-range hybrid control strategy in the comprehensive case, this paper carries out variable speed operation of AGV in the full-speed range under the premise of BLDC load 0.3 N·m. By sorting out the data, the simulation results of five stages with obvious jitter are obtained, as shown in Figure 17.
The simulation results show that the BLDC output speed waveform is stable under the hybrid control strategy. Although there is an overshoot, it does not exceed 1.5%, and the maximum chattering does not exceed 6.1 rad/min. It can run stably with or without load conditions. The control algorithm satisfies the instantaneous acceleration and deceleration of BLDC. Based on the high-precision measurement distance of obstacles in the garage, this paper studies the control of BLDC and considers that the specific position of AGV is the integration of speed in the running time, so the specific position of AGV in the intelligent garage can be accurately determined, so as to avoid collision and realize the high safety of AGV in the garage. Therefore, the research content of this paper meets the requirements of AGV driving reliability and safety.

6. Conclusions

This paper takes the design of an intelligent garage AGV obstacle avoidance system as the object. Under the premise that the accuracy of the ranging module is 0.17 cm, the design of the driving system in the full speed range is discussed, and the simulation model is built in Matlab/Simulink. According to the BLDC speed output curve under this system, it is found that the dual closed-loop vector control based on a photoelectric sensor has an excellent control effect in the low- and medium-speed stages, but the control effect does not meet the actual needs in the high-speed stage, so the speed measurement is switched to SMO to improve the stability of the speed output curve. This method can not only reduce the jitter value by 50%, but can also remove the phase error of encoder speed measurement. In the high-speed stage of BLDC, compared with the sensing FOC motor control, the sensorless sliding mode observation algorithm directly adjusts the system gain according to the motor running state, which has strong robustness. Two different speed sensors are used in the full speed range, a reasonable sensor switching threshold is selected, and the output speed curve is better in terms of dynamic and steady-state performance, which aligns with the actual production needs.
Through the output curve under the SMO, it is known that the speed waveform still fluctuates after reaching stability, which is related to the following parameters: the parameters of the motor, the synovial gain in the SMO algorithm, the parameters of the low-pass filter, and the PI controller parameters in the phase-locked loop. Subsequent research will optimize these parameters. Finally, it should be considered that the over-modulation of the PI controller during the acceleration of the motor will cause jitters in the feedback speed. In addition, considering that during the acceleration of the BLDC motor, the over-modulation of the PI controller will also cause the jitter of the feedback speed. Therefore, when the chattering gap between the output speed of the photoelectric encoder and the SMO is slight, the modulation effect of the PI controller has a great influence, and the superiority of the SMO is difficult to reflect. Finally, this will be further studied in the future.

Author Contributions

Conceptualization, X.Z. and L.W.; methodology, X.Z. and L.W.; software, X.Z. and Z.L.; validation, L.W.; formal analysis, X.Z. and S.L.; investigation, X.Z.; resources, L.W.; writing—original draft preparation, X.Z., L.W. and Z.L.; writing—review and editing, X.Z.; project administration, L.W.; funding acquisition, L.W. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

All data are contained within the article.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Jiang, N.; Han, Y.Y. Patent Technology Development of Intelligent Stereo Garage. China Sci. Technol. Inf. 2024, 14, 31–33. (In Chinese) [Google Scholar]
  2. Bhargava, A.; Suhaib, M.; Singholi, A.S. A review of recent advances, techniques, and control algorithms for automated guided vehicle systems. J. Braz. Soc. Mech. Sci. Eng. 2024, 46, 419. [Google Scholar] [CrossRef]
  3. Wang, L.J.; Dai, M.; Liu, C.Q.; Zhou, Z. Three-closed-loop motor control system in intelligent measurement and control of a three-dimensional garage. J. Electr. Mach. Control. 2020, 24, 107–115. (In Chinese) [Google Scholar]
  4. Nair, D.S.; Jagadanand, G.; George, S. Sensorless direct torque controlled BLDC motor drive with Kalman filter algorithm. In Proceedings of the IECON 2017—43rd Annual Conference of the IEEE Industrial Electronics Society, Beijing, China, 29 October 2017–1 November 2017. [Google Scholar]
  5. Mamadapur, A.; Mahadev, G.U. In Speed control of BLDC motor using neural network controller and PID controller. In Proceedings of the 2019 2nd International Conference on Power and Embedded Drive Control (ICPEDC), Chennai, India, 21–23 August 2019. [Google Scholar]
  6. Al-Mutayeb, Y.; Almobaied, M.; Ouda, M. Real-Time Simulation and Experimental Implementation of Luenberger Observer-Based Speed Sensor Fault Detection of BLDC Motors. Acta Mech. Autom. 2024, 18, 144–157. [Google Scholar] [CrossRef]
  7. Kristiyono, R.; Wiyono, W. Autotuning Fuzzy PID Controller for Speed Control of BLDC Motor. J. Robot. Control (JRC) 2021, 2, 400–407. [Google Scholar] [CrossRef]
  8. Mohanraj, D.; Aruldavid, R.; Verma, R.; Sathiyasekar, K.; Barnawi, A.B.; Chokkalingam, B.; Mihet-Popa, L. A Review of BLDC Motor: State of Art, Advanced Control Techniques, and Applications. IEEE Access 2022, 10, 54833–54869. [Google Scholar] [CrossRef]
  9. Li, W.P.; Baimin, A.; Gahfu, A.; Gulibahar, T. Experimental test of ultrasonic range measurement and obstacle avoidance system for mobile robot. Mach. Tools Hydraul. 2022, 50, 1–5. (In Chinese) [Google Scholar]
  10. Maybeck, P.S. The Kalman Filter: An Introduction to Concepts. Autonomous Robot Vehicles Ingemar, 1st ed.; Cox, J., Wilfong, G.T., Eds.; Springer: New York, NY, USA, 1990; Volume 15, pp. 194–204. [Google Scholar]
  11. Kim, Y.; Bang, H.J.I. Introduction to Kalman Filter and Its Applications. Introduction and Implementations of the Kalman Filter, 2nd ed.; Govaers, F., Ed.; BoD–Books on Demand: Norderstedt, Germany, 2019; Volume 2, pp. 3–19. [Google Scholar]
  12. Li, J.Z. Research on Ultrasonic Localization Based on Modal Optimized Kalman Filtering; Shandong Normal University: Shandong, China, 2015. (In Chinese) [Google Scholar]
  13. Zhang, P.F.; Sheng, H. Interactive multi-model Kalman filtering algorithm based on multiple speed and distance measurements. Inf. Technol. Informatiz. 2024, 6, 146–149. (In Chinese) [Google Scholar]
  14. Qian, R.; Feng, C.T. Research on the localization of two-wheeled differential robot based on multi-sensor fusion. Electron. Fabr. 2024, 32, 103–132. (In Chinese) [Google Scholar]
  15. Guo, Y. Structure and Control System Design of Parking Robot in Underground Garage; Chang’an University: Shanxi, China, 2020. (In Chinese) [Google Scholar]
  16. Yao, G.; Feng, J.; Wang, G.; Han, S. BLDC Motors Sensorless Control Based on MLP Topology Neural Network. Energies 2023, 16, 4027. [Google Scholar] [CrossRef]
  17. Sanchez-Brea, L.M.; Morlanes, T. Metrological errors in optical encoders. Meas. Sci. Technol. 2008, 19, 115104. [Google Scholar] [CrossRef]
  18. Li, W.; Xu, Z.; Zhang, Y. Induction motor control system based on FOC algorithm. In Proceedings of the 2019 IEEE 8th Joint International Information Technology and Artificial Intelligence Conference (ITAIC), Chongqing, China, 24–26 May 2019. [Google Scholar]
  19. Chao, W.; Qiang, G.; Jing, T. An Implementation Method of SVPWM Modulation Algorithm. In Proceedings of the IOP Conference Series: Materials Science and Engineering (AIAAT), Beijing, China, 1–3 August 2019. [Google Scholar]
  20. Liu, X.; Wang, Z.; Wang, W.; Lv, Y.; Yuan, B.; Wang, S.; Li, W.; Li, Q.; Zhang, Q.; Chen, Q. SMO-Based Sensorless Control of a Permanent Magnet Synchronous Motor. Front. Energy Res. 2022, 10, 839329. [Google Scholar] [CrossRef]
  21. Jin, A.J.; Wang, J.Z.; Chen, Q.C.; Lu, Y.X.; Yuan, K.P.; Zheng, T.X. Design of a brushless DC motor system based on a slip film observer. Agric. Equip. Veh. Eng. 2019, 57, 1–5. (In Chinese) [Google Scholar]
  22. Zhang, Z.; Xiong, G.; Wang, J.; Zhang, X.; Wang, S.; Wang, X. A SMO Based Position Sensorless Permanent Magnet Synchronous Motor Control Strategy. In Proceedings of the 2020 15th IEEE Conference on Industrial Electronics and Applications (ICIEA), Kristiansand, Norway, 9–13 November 2020. [Google Scholar]
  23. Jiang, T.Y.; Li, W.; Zhu, C.; Wang, W.W.; Yang, Y.M.; Qiu, Z.Y. A PMSM dual closed-loop PI controller tuning method based on frequency domain analysis. J. Artill. Firing Control 2024, 45, 52–61. (In Chinese) [Google Scholar]
  24. Girija, P.; Prince, A. Robustness evaluation of SMO based speed-position estimation in BLDC motor. In Proceedings of the 2014 International Conference on Advances in Electrical Engineering (ICAEE), Vellore, India, 9–11 January 2014. [Google Scholar]
  25. Mingxia, C.; Yuguang, Z. Simulation Research on Sensorless Speed Control System of Permanent Magnet Synchronous Motor Based on SMO. In Proceedings of the 2016 Eighth International Conference on Measuring Technology and Mechatronics Automation (ICMTMA), Macau, China, 11–12 March 2016. [Google Scholar]
  26. Du, S.; Zhang, Z.; Wang, J.; Wang, K.; Zhao, H.; Li, Z. Integrated Predictive Control of PMLSM Current and Velocity Based on ST-SMO. Energies 2022, 15, 5504. [Google Scholar] [CrossRef]
Figure 1. Working sequence diagram of HC-SR04.
Figure 1. Working sequence diagram of HC-SR04.
Sensors 24 05694 g001
Figure 2. Effect of data filtering.
Figure 2. Effect of data filtering.
Sensors 24 05694 g002
Figure 3. BLDC equivalent circuit.
Figure 3. BLDC equivalent circuit.
Sensors 24 05694 g003
Figure 4. The structure schematic diagram of photoelectric encoder.
Figure 4. The structure schematic diagram of photoelectric encoder.
Sensors 24 05694 g004
Figure 5. Photoelectric encoder interface circuit diagram.
Figure 5. Photoelectric encoder interface circuit diagram.
Sensors 24 05694 g005
Figure 6. FOC control algorithm structure.
Figure 6. FOC control algorithm structure.
Sensors 24 05694 g006
Figure 7. SVPWM space vector diagram.
Figure 7. SVPWM space vector diagram.
Sensors 24 05694 g007
Figure 8. Three-phase PWM waveform of the first sector.
Figure 8. Three-phase PWM waveform of the first sector.
Sensors 24 05694 g008
Figure 9. Dual closed-loop control system simulation.
Figure 9. Dual closed-loop control system simulation.
Sensors 24 05694 g009
Figure 10. Current closed-loop transfer function.
Figure 10. Current closed-loop transfer function.
Sensors 24 05694 g010
Figure 11. SMO simulation module.
Figure 11. SMO simulation module.
Sensors 24 05694 g011
Figure 12. Speed feedback waveform of photoelectric encoder.
Figure 12. Speed feedback waveform of photoelectric encoder.
Sensors 24 05694 g012
Figure 13. Comparison of full-speed-range velocity waveform.
Figure 13. Comparison of full-speed-range velocity waveform.
Sensors 24 05694 g013
Figure 14. Feedback speed waveform comparison.
Figure 14. Feedback speed waveform comparison.
Sensors 24 05694 g014
Figure 15. Comparison of speed feedback waveforms in high-speed range.
Figure 15. Comparison of speed feedback waveforms in high-speed range.
Sensors 24 05694 g015
Figure 16. Comparison of rotor position waveforms under three different conditions.
Figure 16. Comparison of rotor position waveforms under three different conditions.
Sensors 24 05694 g016
Figure 17. Full-speed-range load constant deceleration feedback waveform.
Figure 17. Full-speed-range load constant deceleration feedback waveform.
Sensors 24 05694 g017
Table 1. Data processing results.
Table 1. Data processing results.
Maximum Error/cmMinimum Error/cmAverage Error/cm
Raw data0.7500.28
Filtered data0.580.0040.17
Table 2. Drive motor parameter requirements.
Table 2. Drive motor parameter requirements.
Rating WRated Torque N·mRated Speed r/min
121.40.961230
Table 3. The corresponding relationship between N and the sector.
Table 3. The corresponding relationship between N and the sector.
N315462
Sector123456
Table 4. Vector action time for each sector.
Table 4. Vector action time for each sector.
N123456
TaZY−Z−XX−Y
TbY−XXZ−Y−Z
T0(T7)(Ts − Ta − Tb)/2
Table 5. Time-switching points of each sector.
Table 5. Time-switching points of each sector.
N123456
CCR1T2T1T1T3T3T2
CCR2T1T3T2T2T1T3
CCR3T3T2T3T1T2T1
Table 6. PI control parameters.
Table 6. PI control parameters.
Kp Ki
Current ring2.511256.6
RPM ring0.010.5
Table 7. Comparison of standard deviation of two algorithms in each speed stage.
Table 7. Comparison of standard deviation of two algorithms in each speed stage.
Speed (rad/min)Standard Deviation—EncoderStandard Deviation—SMO
8909.9313.70
9005.7612.66
9102.004.03
9203.142.12
9302.151.99
9403.272.00
9502.411.84
9603.672.22
9702.482.44
9804.032.14
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Wang, L.; Zhu, X.; Li, Z.; Li, S. Ultrasonic Obstacle Avoidance and Full-Speed-Range Hybrid Control for Intelligent Garages. Sensors 2024, 24, 5694. https://doi.org/10.3390/s24175694

AMA Style

Wang L, Zhu X, Li Z, Li S. Ultrasonic Obstacle Avoidance and Full-Speed-Range Hybrid Control for Intelligent Garages. Sensors. 2024; 24(17):5694. https://doi.org/10.3390/s24175694

Chicago/Turabian Style

Wang, Lijie, Xianwen Zhu, Ziyi Li, and Shuchao Li. 2024. "Ultrasonic Obstacle Avoidance and Full-Speed-Range Hybrid Control for Intelligent Garages" Sensors 24, no. 17: 5694. https://doi.org/10.3390/s24175694

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Article metric data becomes available approximately 24 hours after publication online.
Back to TopTop