Loading...

Table of Content

    16 February 2023, Volume 37 Issue 1 Previous Issue    Next Issue
    "Intelligent Vehicle Perception and Control in Complex Environments" special column

    Research on dynamic vision algorithm of FSAC racing cars

    2023, 37 (1):  1-8. 
    Abstract ( 217 )   PDF (2961KB) ( 204 )   Save
    Aiming at the problem that the number of cone obstacles obtained in the view of a curved racing track is small for driverless FSAC racing cars for college students in China under a high-speed turning condition, which is easy to lead to failure of path planning, this paper designs a dynamic vision algorithm based on lidar and inertial navigation. The algorithm detects the cone obstacles based on the information of lidar. At the same time, the algorithm obtains the change of the heading angle by using inertial navigation solution, and performs weighted moving average filtering on the change of the heading angle to predict its change trend at the next moment. Combined with the speed and wheel angle information, the algorithm calculates and adjusts the range of the region of interest so as to keep the perceptual vision in the center of the racing track and obtain more information of cone obstacles at the turning. The algorithm is verified by real vehicle experiments. The results show that it effectively improves the perception efficiency and the path planning ability of the car.
    Related Articles | Metrics

    Research on the integrated vehicle positioning algorithm in complex urban environments

    2023, 37 (1):  9-18. 
    Abstract ( 182 )   PDF (3750KB) ( 156 )   Save

    In recent years, with the rapid development of intelligent driving technology, the requirements of vehicles for environmental perception, positioning, decision-making, control and other systems are increasing. As a prerequisite and basis for other systems, real-time and accurate positioning of a vehicle has important research values. The Global Navigation Satellite System (GNSS) can provide absolute positioning results without accumulative errors, but it has weak resistance to interference and low output frequency. Inertial Navigation System (INS), on the other hand, has a high sampling frequency and good real-time performance, but cannot be used alone for long periods of time due to the accumulative errors. As the combination of the two can effectively complement each other, the GNSS/INS integrated positioning algorithm is widely used as a mainstream positioning method in the field of vehicle navigation and positioning.

    However, as the main working condition of a vehicle, an urban environment is complex, causing challenges for vehicle positioning systems. Tall buildings, trees and overpasses in an urban environment can block satellite signals, resulting in a significant reduction in GNSS positioning accuracy. When using the Kalman filter to fuse GNSS and INS measurements, a vehicle may receive anomalous GNSS positioning results, which can lead to reduced performance of the integrated vehicle positioning system and cause driving safety problems if the filter parameters are not adjusted in a timely and accurate way.

    Aiming at the problem of a reduced positioning accuracy of the integrated vehicle positioning system due to GNSS signal anomalies in urban environments, this paper proposes a fuzzy adaptive Kalman filter-based integrated vehicle positioning algorithm. The algorithm makes full use of the auxiliary information provided by GNSS (the number of visible satellites and position dilution of precision), builds a fuzzy inference system to monitor them and outputs the adjustment coefficient of measurement noise. The improved Sage-Husa algorithm is then used to further estimate the measurement noise based on the filter innovation. Combining the above methods, the covariance of the measurement noise in the filter parameters is adjusted timely and accurately by fuzzy adaptive estimation. Using the vehicle position error, velocity error, orientation error and the error in the bias of the accelerometer and gyroscope in three axis as state vectors, the Error State Kalman Filter (ESKF) is used to fuse the GNSS and INS measurements by replacing the fixed filter parameters of the standard ESKF with the measurement noise covariance obtained by the fuzzy adaptive estimation algorithm described above. At the same time, with reference to the kinematic characteristics of the ground vehicle, the kinematic constraints of the vehicle are constructed to further correct the errors of the GNSS/INS integrated positioning system by means of measurement updates.

    The performance of the proposed algorithm is verified by computer simulation and real vehicle experiments. The results show that the proposed fuzzy adaptive Kalman filter-based integrated vehicle positioning algorithm can adjust the measurement noise covariance in a timely and accurate way and correct the positioning error by vehicle kinematic constraints, and it can still provide accurate positioning results in areas where GNSS signals are anomalous. The positioning accuracy of the proposed algorithm is significantly improved compared to the standard ESKF algorithm.

    Related Articles | Metrics

    Visual SLAM based on key targets in a complex traffic environment

    2023, 37 (1):  19-25. 
    Abstract ( 165 )   PDF (2177KB) ( 192 )   Save

    Visual simultaneous localization and mapping(SLAM) plays an important role in autonomous driving. However, it is difficult for the current visual SLAM algorithm to solve those complex traffic scenes where few nearby textures but a large amount of dynamic object occlusion such as moving cars exists. Therefore, this paper proposes a visual SLAM algorithm based on key objects. The algorithm consists of five parts—key object extraction, system initialization, tracking based on key targets, pose solution and local bundle adjustment(BA).

    First of all, based on stationary targets detected by the environment perception algorithm in typical traffic scenes such as traffic signals and signs, this paper performs feature extraction in stationary targets and uses the quad tree to homogenize the feature points. According to the number of feature points, the key targets are screened and the process of key object extraction is finished.

    Secondly, the key target matching between the two continuous frames is performed in order to help system initialization. The matching criteria consist of the center, the height and the width of the key targets. System initialization is launched when the number of the matched key targets satisfies the need. RANSAC algorithm is used in feature point selection to compute the initial pose. A local map and map points are established at the end of the system initialization.

    Then, the constant motion model is applied to predict the center point of the key targets in the following frame. Besides the height and the width of the key targets, the number of the matched points is also taken into account to decide which key target in the current frame matches the corresponding one best.

    Furthermore, after data association is completed, the camera pose is estimated based on the feature points and the center point of each key target. Reprojection error is chosen to optimize the pose and distinguish the inliers and outliers in the process of optimization iteration.

    Lastly, local BA is utilized in local mapping thread in order to reduce accumulative error. Levenberg-marquardt(LM) algorithm is used as the optimization algorithm and the optimization variables include the pose of the key frame, the center point of each key target and the 3D coordination of feature points in key targets.

    To verify the performance of the proposed algorithm, the typical scenes in ApolloScape dataset are chosen. Experiments show that the proposed algorithm can effectively solve the problem of localization failure in some near-texture missing environments, and maintain a high localization accuracy, which has a good environmental adaptability.

    Related Articles | Metrics

    Artificial potential field design and collision avoidance path planning under visual perception

    2023, 37 (1):  26-36. 
    Abstract ( 199 )   PDF (6198KB) ( 200 )   Save
    Aiming at the path planning problem of collision avoidance and overtaking for intelligent vehicles, this paper proposes an innovative artificial potential field method based on visual perception of the road environment by using monocular cameras so as to provide necessary information for path planning. For structured roads, inverse perspective transformation is adopted to eliminate the projection characteristics of visual images. Thus, the parameters of lanes are determined according to the parallel relationship of lane lines and the algorithm of random sampling consensus, which improves the accuracy of lane detection. Based on this, a ground ranging model is proposed and used to measure the width of a lane. Next, a YOLO-3DBOX network structure is proposed to obtain the information of vehicles ahead on the road. At first, YOLOv4 is adopted to achieve two-dimensional detection of the vehicle. Then, with the help of the idea of Deep3DBOX, prediction bias and geometric projection constraints are used to regress the dimension, orientation angle and center coordinates of the vehicle, and finally to achieve three-dimensional detection of the target. So far, the obtained complete perception information of roads and vehicles can be used to design artificial potential fields for autonomous driving. Firstly, the gravitational potential field of the main lane is designed to guide the controlled vehicle to drive forward in the main lane. Then, according to the driving specifications for vehicles on road, the road boundary in the potential field is designed to avoid the controlled vehicle crossing the center line of the lane or the road boundary. Next, the collision avoidance area is designed according to the relative velocity between the controlled vehicle and the vehicle in front to constrain the range of the potential field of the road boundary and the repulsion field of obstacles. Meanwhile, the repulsion field of obstacles is constructed by using exponential and trigonometric functions. According to the kinematic constraints of the vehicle, the sine function is used to adjust the transverse and longitudinal parameters to ensure that the planned path can avoid obstacles smoothly and conform to the steering characteristics of the vehicle. In order to verify the effectiveness of the proposed algorithm, the planned paths are compared and analyzed under various simulation conditions. Simulation results show that the improved artificial potential field algorithm fully considers the road boundary and vehicle constraints, and can complete path planning on straight and curved roads. The controlled vehicle can avoid and overtake static and dynamic obstacles at different speeds. In the process of obstacle avoidance, the controlled vehicle always keeps a sufficient safe distance from the obstacle, and returns to the original lane in time after overtaking. In addition, Carsim/Simulink software is used to carry out co-simulation of path tracking. The maximum of both lateral error and heading angle deviation of the vehicle are 0.094 m and 0.021 rad in the tracking process, which proves that the planned path can guarantee that the vehicle has good tracking performance. Finally, in order to further verify the feasibility of the system, an experiment is carried out on the FR-08 wire chassis platform. The experimental results show that the proposed algorithm can plan and track the path for obstacle avoidance according to information of the road and the vehicle ahead. The maximum lateral error between the actual trajectory and the planned path is 0.105 m, and the maximum error of the heading angle is 0.092 rad. The simulation and experiment results show that the proposed algorithm for collision avoidance and overtaking of intelligent vehicles can realize the information perception of road environment, and, at the same time, plan and track a reasonable path that conforms to the kinematic characteristics of vehicles.
    Related Articles | Metrics

    Research on TSK fuzzy extension control of human simulated lane-changing of intelligent vehicles

    2023, 37 (1):  37-46. 
    Abstract ( 98 )   PDF (3454KB) ( 104 )   Save
    Intelligent vehicles have become a research hotspot in academia and industry, mainly because the driving tasks of intelligent vehicles can be performed by the auto drive system, which greatly reduces the driving burden of human drivers and improves driving efficiency and safety. A large number of traffic jams and casualties are caused by the factor of “people”, and automatic driving can eliminate the hidden danger of “people” from the “people-vehicle-road” system, thereby greatly enhancing the safety of road traffic. Relevant research shows that the difference between an autonomous vehicle and a skilled driver is that the former gives people less comfort in steering and other operations. As one of the key operations of vehicles in the driving process, lane changing puts forward higher requirements for the transverse and longitudinal control of vehicles. In order to improve the tracking accuracy and occupant comfort of an intelligent vehicle in autonomous lane changing, this paper proposes a control method of intelligent vehicle lane changing by imitating human beings, which combines the extension control with TSK (Takagi Sugeno Kang) fuzzy control. First of all, five driving school coaches with rich driving experience are recruited as representatives of skilled drivers, the lane change track data of skilled drivers are collected by a combination of real vehicles and driving simulators, and the test track is analyzed to study the impact of different factors on lane change path. The behavior of intelligent vehicle lane changing has strong nonlinear characteristics. Based on generalized regression neural network (GRNN), a path planning model for human like lane changing is designed. Secondly, the relationship between preview position deviation and the yaw angle is derived so as to establish the “vehicle road” system model by analyzing the preview characteristics of skilled drivers and combining the preview deviation, road environment and vehicle state. In order to improve the tracking accuracy and occupant comfort of intelligent vehicles under different lane changing conditions, a humanoid trajectory tracking controller based on extension theory is designed. The controller can be divided into upper and lower layers. The upper layer controller mainly extracts the tracking characteristics of intelligent vehicles and divides the classical domain, extension domain and non domain. In order to meet the control requirements of intelligent vehicles in different control domains, the lower controller adopts PID feedback control based on road curvature and emergency braking respectively, which solves the limitations of a single control method and realizes accurate control in the global range. Because the extension control will produce control quantity jitter at the switching point, and the local stability will be affected, an optimization method based on TSK fuzzy theory is proposed to further improve the global stability and tracking accuracy of the extension control. By analyzing the results of joint simulation, it can be concluded that the extension control method based on TSK fuzzy theory proposed in this paper has higher control accuracy and stability.
    Related Articles | Metrics

    Research on the layered energy management strategy of hybrid electric vehicles in the networked environment

    2023, 37 (1):  47-55. 
    Abstract ( 140 )   PDF (3711KB) ( 236 )   Save
    Based on urban roads, this paper proposes a layered model predictive control (MPC) to plan car speeds to reduce frequent start and stop of hybrid electric vehicles, improve traffic efficiency, and achieve fuel economy through energy management. The upper-layer MPC uses the intelligent network technology to obtain states like speed and position of the vehicle in front, and predicts the optimal speed of the vehicle to avoid stopping at red lights by combining the traffic environment data. The lower-layer MPC manages the energy of hybrid electric vehicles according to the optimal speed to improve fuel economy. The comparison between the energy management results of the layered MPC and those of dynamic programming at the same speed shows that the proposed method can effectively avoid vehicle idling at red lights and improve fuel economy and traffic efficiency.
    Related Articles | Metrics

    An end-to-end autonomous driving strategy based on the deep deterministic gradient algorithm

    2023, 37 (1):  56-65. 
    Abstract ( 199 )   PDF (1688KB) ( 251 )   Save

    The continuous progress of artificial intelligence has pushed cars into an intelligent era. At present, the common automatic driving scheme adopts a hierarchical architecture of perception decision control. Such a model has many difficulties: 1. Rule-based strategies require a lot of manual design, which not only requires complex processes, but also costs a lot; 2. It is unable to adapt to a densely populated and complex urban traffic environment; 3. The lower module is closely connected with the upper module, and the maintenance of the system is cumbersome and miscellaneous. In view of these problems, this paper uses the Carla urban driving simulator to conduct simulation experiments on lane keeping tasks of intelligent driving with a deep deterministic policy gradient algorithm, aiming to solve the problem of over dependence on traditional upper and lower modules through end-to-end control methods. Secondly, because the algorithm is a combination of reinforcement learning and deep learning, according to the characteristics of reinforcement learning, irregular trial and error are required in the training process, and they are too costly for vehicle driving. Therefore, in view of the characteristic that the deep deterministic policy gradient algorithm needs trial and error, based on this algorithm, a real-time monitor for dangerous automobile behaviors is designed between the environment and the agent, which can constrain and correct the dangerous behaviors of the agent so as to reduce trial and error behaviors and improve the training efficiency.

    The deep deterministic policy gradient algorithm and the supervised deep deterministic policy gradient algorithm have trained 70 000 episodes respectively in the Carla simulation environment. The simulation results show that the two algorithms have finally achieved the same training effect, can effectively avoid obstacles, and make the driver drive normally without violating driving rules, but the latter has a faster convergence speed. Secondly, taking the map, the number of dynamic factors and weather as the control variables, the two algorithm models are evaluated and tested under a unified evaluation scheme of the experimental platform with a lane keeping task. Finally, the supervised deep deterministic policy gradient algorithm achieves 98% and 89% of the average task completion in the environment without and with dynamic factors respectively, while the DDPG achieves 97% and 88% of the average task completion respectively also in the two above mentioned environments.

    The deep deterministic policy gradient algorithm is used to control the autonomous vehicle end to end, which not only effectively improves the disadvantages of the heavy dependence on the upper and lower modules in the traditional scheme, but also shortens the development cycle. Although the final control effect of the supervised reinforcement learning is the same as that of the original algorithm, it significantly improves the convergence speed and effectively reduces the early trial and error frequency of agents. Therefore, the combination of supervised learning and reinforcement learning can provide a new solution to reduce the risk of trial and error in reinforcement learning, and provide a certain reference value for the realization of end-to-end intelligent driving from simulation to the practical application of in-deep reinforcement learning.

    Related Articles | Metrics

    Lateral tracking control of a driverless four-wheel steering vehicle under extreme conditions

    2023, 37 (1):  66-74. 
    Abstract ( 206 )   PDF (3557KB) ( 285 )   Save
    In order to improve the trajectory tracking accuracy of driverless four-wheel steering vehicles under extreme conditions of different road adhesion coefficients, this paper proposes a trajectory tracking control strategy. A vehicle three-degree-of-freedom dynamic model is established as the controller prediction model and the front wheel steering controller is designed through predictive model control theory. Considering the effect of the center-of-mass slip angle on vehicle stability, a rear wheel steering controller is designed based on the fuzzy control theory. A co-simulation model is established in Matlab/Simulink and CarSim software platforms. The high-speed turning condition on high-adhesion roads and the medium-speed turning condition on low-adhesion roads are selected for comparative experiments. The results show that, considering the center-of-mass slip angle, the rear wheel steering controller ensures the high-speed steering stability of the driverless four-wheel steering vehicle. At the same time, compared with the rear wheel angle controller without considering the center-of-mass slip angle, the trajectory tracking accuracy improves about 25%
    Related Articles | Metrics

    Test-based extraction and identification of key scenarios for digital twins of intelligent networked vehicles

    2023, 37 (1):  75-84. 
    Abstract ( 221 )   PDF (2082KB) ( 202 )   Save
    Scenario generation is one of the key problems in digital twin (DT) technology, and the typicality of scenarios is the key to test effectiveness. The test scenarios of an intelligent networked vehicle are derived from real vehicle driving data. This paper proposes a new DT test scene generation method which extracts typical test scenes based on local road vehicle driving data collected by roadside radar, establishes a typical scene evaluation method of collision risk factors and traffic quality factors on the basis of the three typical applications of FCW, LCW and ICW, and builds an LSTM-AE-Attention model to identify these critical scenarios. The experimental results show that the constructed model can effectively evaluate and identify typical scenes, which provides effective support for the construction of the test scene library.
    Related Articles | Metrics
    Mathematics·Statistics

    A small probe-type flow and temperature composite sensor based on fiber Bragg grating

    2023, 37 (1):  85-91. 
    Abstract ( 122 )   PDF (3433KB) ( 175 )   Save
    Aiming at the problems of huge pressure loss, narrow measurement range and a complex structure of a fiber Bragg grating (FBG) flow and temperature composite sensor, this paper proposes a small FBG-based probe-type flow and temperature composite sensor. Firstly, based on the bending deformation theory of cantilever beams and the FBG sensing principles, the probe-type flow and temperature composite sensor model is established combined with the flow velocity distribution characteristics of the fluid in the pipeline, and the mapping relationship between the central wavelength drift and flow and temperature of FBG is revealed. Secondly, the strain distribution characteristics of the probe structure are studied by finite element analysis method, and the optimal sticking position of the FBG is determined. Finally, an experimental system platform is established, and temperature and flow sensing experiments are carried out. The results of the temperature experiment show that the temperature sensitivity of the sensor is 25 pm/℃, which is 2.3 times that of the bare FBG, and the repeatability error is 3.621%. The flow experiment results show that the measurement range of the sensor is from 2 m3/h to 30 m3/h, and the repeatability error is 2.141%. Compared with the existing FBG flow and temperature composite sensors, the proposed sensor has smaller pressure loss and wider measurement range
    Related Articles | Metrics

    Research on the life prediction method of rolling bearings driven by the multi-module U-Net-BiLSTM network

    2023, 37 (1):  92-100. 
    Abstract ( 102 )   PDF (4626KB) ( 127 )   Save
    Aiming at the problem that it is difficult for the rolling bearing life prediction method to accurately identify the first predicting time (FPT) and extract the deep features of the time series, this paper proposes a rolling bearing life prediction method combining high-precision FPT points and the multi-module U-Net-BiLSTM network. After wavelet noise reduction, all frequency components in the power spectrum of the original signals at each moment are accumulated and summed, and the Euclidean distance criterion and the 3σ principle are combined to identify high-precision FPT points; the residual blocks, pooling layers and normalization layers are respectively introduced into the encoder and the decoder to achieve multi-scale feature fusion, thereby upgrading the traditional U-Net network and effectively improving the process ability and prediction speed for time series signals of the model. The experimental results show that this method has higher prediction accuracy and faster prediction speed than the existing three deep learning comparison method
    Related Articles | Metrics

    Research on feature extraction of steady-type gear faults with sparse representation auto-encoder network

    2023, 37 (1):  101-110. 
    Abstract ( 88 )   PDF (4189KB) ( 112 )   Save
    Due to the interference of noise, equipment eccentricity and other factors, it is hard to accurately extract the steady-type fault parameters of fixed-shaft gears. Additionally, the features extracted by intelligent diagnosis methods are often abstract and difficult to explain. To solve this problem, firstly, an interpretable sparse representation Auto-Encoder network is designed based on the steady-type fault response mechanism and sparse representation theory. The encoding and decoding layers of Auto-Encoder network are equivalent to the solution of the sparse vector and learning of the over complete dictionary respectively. Based on the characteristics of steady-type fault signal parameters, an adaptive optimization algorithm is then designed to realize the fast-global optimization of characteristic parameters. Combining the designed sparse representation Auto-Encoder network and the steady-type fault signal features of fixed-shaft gears, a deep neural network is built to achieve a high-precision feature reconstruction of steady-type fault signals. Finally, the simulation shows that the proposed method can directly extract steady-type fault feature parameters with a clear physical meaning, and has high feature extraction accuracy and good anti-noise performance, which further verifies the effectiveness of the proposed method.
    Related Articles | Metrics

    Straightening stroke prediction based on the improved fuzzy neural network

    2023, 37 (1):  111-119. 
    Abstract ( 66 )   PDF (2652KB) ( 129 )   Save
    Aiming at the problems of low accuracy and long time consumption of straightening stroke prediction of shaft straightening machines, this paper proposes an improved fuzzy neural network model. The system framework of the prediction model is a combination of the fuzzy system and the neural network, and a connection layer is designed in the network structure, which can give feedback to the historical data of the straightening stroke and enhance the network data processing ability. Relevant factors affecting the straightening stroke are taken as reference indexes, successful real-time straightening data are taken as model input, and the straightening stroke is taken as model output. Compared with the traditional prediction methods, the experimental results show that the relative error between the actual value and the predicted value of the improved fuzzy neural network is 1.65%, achieving an improvement in the prediction accuracy of the straightening stroke and the straightening efficiency.
    Related Articles | Metrics

    Influence and multi-objective optimization of parameters of pressure straightening effect of pipe fittings

    2023, 37 (1):  120-131. 
    Abstract ( 102 )   PDF (9053KB) ( 29 )   Save
    Pressure straightening can flexibly adjust the straightening method according to different bending situations and repair the deformed workpiece. The straightening effect of a pipe is influenced by its own materials, structural parameters and straightening process parameters. To this end, this paper firstly establishes a finite element numerical simulation model of the pressure straightening process of the pipe, verifies the accuracy of the model, and then investigates the influence of its own material parameters (modulus of elasticity and yield strength), structural parameters (wall thickness and internal diameter) and pressure straightening process parameters (downward pressure amount and pivot distance) of a pipe on the straightening effect. On this basis, a multi-objective optimization model is established with the straightening process parameters (downward pressure amount and pivot distance) as design variables, the pivot distance and down pressure amount as design constraints, and the residual deformation and residual equivalent force after unloading as optimization objectives. The results show that, after optimization, the residual stress of the pipe fittings reduces by 103.207 MPa and the residual deformation reduces by 0.349 mm, which provides reference for improving the pressure straightening effect of the pipe fittings.
    Related Articles | Metrics
    Information and computer science

    Research on the path planning algorithm of an orchard hedge pruning manipulator

    2023, 37 (1):  132-139. 
    Abstract ( 100 )   PDF (2891KB) ( 99 )   Save
    To improve planning efficiency, shorten path length and ensure a smooth operation of a hedgerow pruning manipulator, this paper proposes a rapidly-exploring random tree algorithm (a-bRRT*) based on gravity and target offset probability. The algorithm introduces the idea of target deflection probability and the gravitational force into the asymptotically optimal rapid exploration random tree RRT* algorithm, which can balance planning efficiency and path length. The comparison of the rapidly exploring random trees based on target offset probability (bias-RRT) with RRT* and a-bRRT* shows that, when the top surface of hedge is being pruned, the path length of a-bRRT* algorithm is 66.32% shorter than bias-RRT, and the planning time is 44.19% shorter than RRT*. When the side of the hedge is being trimmed, the path length of a-bRRT* algorithm is 67.17% shorter than bias-RRT, and the planning time is 73.87% shorter than RRT*. The simulation results show that the proposed a-bRRT* algorithm greatly improves the search efficiency and shortens the path length.
    Related Articles | Metrics

    Research on fault feature selection of the chiller using the improved lightning search algorithm

    2023, 37 (1):  140-148. 
    Abstract ( 89 )   PDF (1111KB) ( 100 )   Save
    This paper proposes a method for fault feature selection of chillers. Firstly, the Fisher Score is used to eliminate a few features that are extremely insensitive to fault categories, and then the improved Lightning Search Algorithm is used to determine the weight of features and the number of features that should be selected. Thus, the final chiller feature subset is obtained. Experiments are carried out on ASHRAE Research Project 1 043 data, and a subset of chiller fault features containing 13 parameters is obtained, most of which are temperature parameters. Furthermore, four methods including k-Nearest neighbors (KNN), random forest (RF), BP neural network and gated recurrent unit (GRU) are used to obtain the diagnostic accuracy of each fault. Partial fault diagnosis accuracy is also improved compared with the original data, verifying the effectiveness of the selected feature subset.
    Related Articles | Metrics

    Study on visual characteristics of novice drivers under fatigue state

    2023, 37 (1):  149-157. 
    Abstract ( 125 )   PDF (3125KB) ( 149 )   Save
    In order to explore the performance of novice drivers’ fatigue characteristics in visual characteristics, this paper designs a driving simulation experiment based on driving simulators and Dikablis Glass 3 eye tracker to collect drivers’ visual data. Combined with the video expert method, drivers’ fatigue levels are divided into awakening, mild fatigue, moderate fatigue and severe fatigue. First of all, the data are cleaned by using Rayda criterion and Kalman filter. Secondly, according to the results of one-way ANOVA and post multiple comparison, mean value of blink duration, mean value of saccade duration, total saccade duration, mean value of pupil area, mean value of pupil variation coefficient, mean value of fixation time and other visual characteristics are selected as the evaluation indexes of drivers’ fatigue driving. Finally, a grey wolf optimized support vector machine (GWO-SVM) fatigue driving recognition model is constructed based on the visual features of novice drivers. The results show that, with the accumulation of driving fatigue of novice drivers, the duration of blinking increases significantly, the saccade duration and total saccade time decrease significantly, the pupil area decreases, and the pupil variation coefficient increases. The SVM identification results show that the fatigue state of novice drivers can be effectively identified by eye movement indicators, and the GWO-SVM model further improves the recognition accuracy, proving that eye movement features have a good applicability in the fatigue detection of novice drivers.
    Related Articles | Metrics

    A modified similarity network fusion algorithm for cover song identification

    2023, 37 (1):  158-165. 
    Abstract ( 73 )   PDF (2046KB) ( 122 )   Save
    This paper proposes the Modified Similarity Network Fusion (MSNF) algorithm, which realizes a direct fusion of non-square matrices by introducing self-built kernel matrices. At the same time, the kernel matrices are fused in advance to avoid the extension of negative influences caused by the kernel matrices constructed based on poorly behaved features. Experimental results on the three datasets demonstrate that the MSNF algorithm achieves higher recognition accuracy than the Similarity Network Fusion algorithm in cover song identification tasks, and greatly reduces the time complexity at the same time.
    Related Articles | Metrics

    Cross-database micro-expression recognition combining attention mechanism and transfer learning

    2023, 37 (1):  166-176. 
    Abstract ( 199 )   PDF (3834KB) ( 280 )   Save
    Factors like a poor generalization ability and overfitting in the training process of the traditional optical flow method cause a low recognition rate of micro-expression. In the feature extraction stage, the convolution network is trained independently and serially at each pyramid level according to the idea of residual structure, and an optical flow vector expression of micro-expression images is refined step by step by combining attention mechanism so as to construct a pyramid optical flow model based on key frames. The final feature representation is obtained by cascading fusion with local binary patterns from three orthogonal planes (LBP-TOP) features, which effectively extracts the spatio-temporal texture features and optical strain information of video sequences. In the aspect of classification model, when the deep learning recognition model is applied to micro-expression classification, convolutional neural network (CNN) cannot achieve a close association between the key facial regions and the corresponding emotional tag vectors, which leads to poor classification performance. Therefore, this paper proposes a transfer learning network framework for micro-expression cross datasets based on CNN and graph convolutional network (GCN) to analyze the concealed relationship between image fusion features and tag vectors, which uses the quantitative advantages of macro-expression to assist micro-expression recognition. Experiments are carried out on two micro-expression databases, CASME II and SAMM, to realize the classification of four kinds of emotion data, and the recognition rate rises from 57.56% to 75.93%.
    Related Articles | Metrics

    Facial expression recognition based on the attention mechanism of deep and wide residual networks

    2023, 37 (1):  177-185. 
    Abstract ( 143 )   PDF (2537KB) ( 143 )   Save
    Aiming at a low accuracy of facial expression recognition and the susceptibility to noise and other factors under natural conditions, this paper proposes a facial expression recognition method that incorporates an improved deep and wide residual network with attention mechanism. A wide residual module structure is formed by increasing the channel number ofresidual units, which effectively alleviates the problem of gradient disappearance caused by excessive network layers.In order to understand facial expressionfornetworks, a compressed and adaptive correction network module is introduced.In order to alleviateover-fitting of the model, the order of the residual units is improved.The original imagesare processed through the improved random erasure method to further strengthen the generalization ability of the model. Experimental results show that the accuracy of the model on fer2013, ck+ data set and JAFFE data set are 72.49%, 99.29% and 94.87%respectively.Compared with other methods, the model proposed in this article has a much higher recognition accuracy and, at the same time,a better robustness.
    Related Articles | Metrics
    Electrical and electronic

    The two-stage siting and sizing model of battery electric truck charging stations

    2023, 37 (1):  186-195. 
    Abstract ( 126 )   PDF (1673KB) ( 152 )   Save
    Aiming at the siting and sizing problem of a battery electric truck charging station, this paper proposes a two-stage siting and sizing model. Firstly, a siting model of a battery electric truck charging station is established in the first stage, with a goal of minimizing the daily food distribution cost of a battery electric truck. Meanwhile, the linking parameters that can be transmitted to the second-stage model are defined in the first-stage model. Secondly, the staying time cost of the truck is introduced based on the queuing theory, and, with a goal of minimizing the annual comprehensive cost of the charging station, a sizing model of the charging station is established in the second stage. Parts of the urban area in Wuhan, Hubei Province are selected as examples in which the food demand is analyzed. Finally, the LINGO software is used to solve the proposed model, and the result indicates the effectiveness of the proposed model.
    Related Articles | Metrics

    Optimal configuration of microgrid capacity for multi-factor polymerized energy storage life

    2023, 37 (1):  196-203. 
    Abstract ( 105 )   PDF (3089KB) ( 155 )   Save
    Aiming at the difficulty of predicting the energy storage life in the optimal configuration of microgrid, this paper proposes a multi-scenario coordinated optimization method of microgrid considering the multi-factor aggregated energy storage life. The microgrid with distributed generation and storage of new energy is taken as the research object. The life loss of the energy storage system is measured by the investment replacement cost, and an energy storage control strategy is formulated, which takes into account of various economic factors, such as investment construction, operation scheduling and equipment life loss. Based on the objective function of minimizing equal annual investment cost and operation cost, a two-layer optimal allocation model of microgrid capacity is established. In this paper, the particle swarm algorithm is used for simulation verification. It is proved that the proposed model and the energy storage control strategy can effectively prolong the service life of energy storage equipment and improve economy and stability of microgrid operation.
    Related Articles | Metrics

    Research on speed control of electromagnetic coupling governors by fuzzy PID control

    2023, 37 (1):  204-211. 
    Abstract ( 119 )   PDF (3325KB) ( 108 )   Save
    In order to improve the control performance and robustness of the speed-current double closed-loop control model of the PI algorithm on the speed of the electromagnetic coupling governors, this paper injects a fuzzy PID algorithm into a speed control loop, models and simulates by Simulink, then uses the PSO algorithm to optimize the control parameters of the fuzzy PID, and carries out the speed control test of the electromagnetic coupling governor by fuzzy PID control. The results show that, compared with the PI algorithm, the optimized target speed reduces the overshoot by 23.31 r/min, the disturbance by 19.8 r/min, and the settling time by 0.101 s. After the test, the fuzzy PID control eliminates the overshoot, and the settling time reduces by 4 s compared with the PID algorithm. The fuzzy PID control algorithm can improve the speed control performance and robustness of the speed-current double closed-loop to the electromagnetic coupling governor, which has a certain optimization effect compared with the PI algorithm and the PID algorithm.
    Related Articles | Metrics

    Linear active disturbance rejection control of dual active bridge DC-DC converters

    2023, 37 (1):  212-220. 
    Abstract ( 113 )   PDF (5021KB) ( 181 )   Save
    Aiming at the high current stress and poor dynamic characteristics of the traditional PI control in single phase shift control of dual active bridge DC-DC converters, this paper proposes a current stress optimization scheme combining linear active disturbance rejection control (LADRC) with direct power control under the extended phase shift (EPS) control with a consideration of current stress and dynamic characteristics of the optimized converters. The global optimal solution of the current stress is derived by establishing a mathematical model under each state of the EPS. The LADRC is introduced into the voltage loop and combined with the DTC. The per unit value of the transmission power is output to the current stress optimization algorithm to calculate the corresponding phase shifting angle. The simulation and the experiment results show that the proposed optimal control strategy can improve the dynamic response of the converter while reducing the current stress.
    Related Articles | Metrics
    Energy, power and environment

    Recycling decisions of e-closed-loop supply chain under financial constraint and fairness preference

    2023, 37 (1):  221-231. 
    Abstract ( 94 )   PDF (1702KB) ( 83 )   Save
    In e-closed-loop supply chain dominated by re-manufacturers and financially constrained by e-commerce platforms, considering the fairness preference of the e-commerce platforms, a Stackelberg game model is established based on the traditional fairness reference frame and the Nash bargaining fairness reference frame respectively. The influence mechanism of financial constraint and fairness preference on the recycling decisions and profits of all parties are analyzed. Then, transfer payment is introduced to optimize the recycling decisions of e-closed-loop supply chain. The research shows that the high loan interest rate is unfavorable to e-closed-loop supply chain operations. The fairness preference is only beneficial to e-commerce platforms, but not to re-manufacturers or e-closed-loop supply chain. Besides, compared with the traditional fairness reference frame, the Nash bargaining fairness reference frame can better alleviate the negative impact of financial constraint and fairness preference on recycling decisions. Finally, no matter whether the fairness preference of the e-commerce platforms exists or not, the introduction of transfer payment can coordinate e-closed-loop supply chain, and Pareto can improve profits of all parties in e-closed-loop supply chain.
    Related Articles | Metrics

    Research on low carbon emission reduction strategies for government and enterprises under the vehicle carbon tax policy

    2023, 37 (1):  232-243. 
    Abstract ( 104 )   PDF (2135KB) ( 107 )   Save
    This paper attempts to introduce the vehicle carbon tax policy to determine the critical conditions for low-carbon technology innovation by enterprises, government regulation and low-carbon travel by consumers. At the same time, the three subjects among them are analyzed. A three-party game model of enterprises, the government and consumers is constructed with the help of the evolutionary game approach to analyze the influence of strategy selection among different subjects and to conduct simulation experiments on the inferred results by using Matlab 2016 software. The simulation results show that the vehicle carbon tax policy can promote enterprise low-carbon technology innovation and low-carbon travel by consumers at the same time. Fraudulent subsidies by enterprises will affect their own motivation to carry out low-carbon technology innovation, and will also lead the government to strengthen the regulation of enterprises. The government’s share of penalties to consumers will be effective in promoting their low-carbon travel, but too much allocation will affect its own regulatory incentives.
    Related Articles | Metrics

    The influence of air inlet velocity on the distribution of turbulent kinetic energy in a water-sparging aerocyclone

    2023, 37 (1):  244-248. 
    Abstract ( 87 )   PDF (2367KB) ( 84 )   Save
    According to the idea of coupling enhancement, the removal process of high concentration ammonia nitrogen wastewater is improved by using hydraulic jet air cyclone mode, and then a water sparging aerocyclone (WSA) is developed. A WSA is a typical gas-liquid mass transfer device, and the research on the turbulent behavior distribution of its internal fluid is particularly important for the design and optimization of the reactor. For this reason, the Reynolds Stress Model (RSM) is used to capture the complex gas-liquid rotational flow, local reflux, and anisotropy of the radial velocity in the reactor. For multiphase flow in the reactor, the Volume of Fluid (VOF) model is used to capture the change law of the intersection interface of gas-liquid two-phase flow. Finally, based on the simulation results, the distribution of turbulent kinetic energy in the WSA is obtained. The results show that the distribution of the turbulent kinetic energy in the lower axial position of the bottom of the overflow pipe is similar, showing an asymmetric saddle shape with high on both sides and low in the middle. The turbulent flow in the overflow pipe area obtains more energy from the time-averaged flow, which means the energy loss of the time-averaged flow in this area is greater than that of turbulence, especially in the axially downward section of the overflow pipe.
    Related Articles | Metrics

    Carbon emission measurement and driving factor analysis of the transportation industry in southwest China

    2023, 37 (1):  249-256. 
    Abstract ( 87 )   PDF (1750KB) ( 135 )   Save
    This paper takes Yunnan, Guizhou and Sichuan provinces in southwest China as examples, and carries out carbon calculation of the transportation industry by using the energy consumption data of the three provinces from 2011 to 2019 through the emission coefficient method. The five common driving factors of energy structure, efficiency, industrial structure, economy and population are quantitatively analyzed, and, combined with the regional characteristics and traffic status of the three provinces, four factors are added for analysis, including public transportation participation, public transportation facility saturation, land use structure and green vegetation coverage. The analysis results show that, from 2011 to 2019, the average values of energy efficiency, residents’ public transportation participation and public transportation vehicle saturation in the three provinces are less than 1, having a suppressive effect on carbon emissions in the transportation industry, of which the most significant average value of energy efficiency inhibition is 0.952; the average value of the remaining six factors is greater than 1, which plays a promoting role, and the significant average value of the promoting role of the regional economic factors is 1.047. Finally, according to the research results, the paper proposes energy conservation and emission reduction for the transportation industry in the three provinces.
    Related Articles | Metrics

    The stability mechanism of soil aggregates during the vegetation recovery process on coalmine dump slopes

    2023, 37 (1):  257-264. 
    Abstract ( 88 )   PDF (1871KB) ( 102 )   Save
    Taking the coalmine dump slopes as the objects, this paper analyzes the effects of slope aspect, slope position and restoration year on the stability of soil aggregates on coalmine dump slopes using Le Bissonnais (LB) method, and studies the damage mechanism of soil aggregates. The results show that, under the three treatments (fast wetting, slow wetting and stirring after prewetting) of LB method, the soil particle size on the dump slopes is mainly in agglomerations >2 mm. The stability of soil aggregates gradually increases from the upper to the lower slope and is better on a shady than on a sunny slope: with an increasing restoration years, these trends are more significant. According to the relative gelatinization index and the relative mechanical crushing index, the clay expansion mechanism has little damage to the soil aggregates, while dissipation and mechanical force are the main mechanisms of the soil aggregates. Therefore, it is necessary to reduce the damage of soil aggregates by external forces such as rainstorms and tillage to improve the stability of the soil structure and promote ecological restoration of coalmine slopes.
    Related Articles | Metrics
    Mathematics·Statistics

    Synchronization of discrete-time phase coupled oscillators with phase shift

    2023, 37 (1):  265-272. 
    Abstract ( 97 )   PDF (1960KB) ( 154 )   Save
    This paper mainly studies both the phase and frequency synchronization of discrete-time Kuramoto oscillators with phase shift. Firstly, a sufficient condition for achieving phase synchronization is established by analyzing the condition under which the maximum phase difference of any two oscillators at the same time tends to be zero. Secondly, when the intrinsic frequencies of the oscillators are nonidentical to each other, a useful bounded property of the phase difference is obtained and then some sufficient conditions for achieving frequency synchronization are derived by setting the upper limit of the phase difference between any two oscillators at the initial time. Finally, the numerical simulations of a system with ten oscillators further show that, when the frequencies of the oscillators are identical to each other, the difference between the maximum and the minimum phases can reduce to 0.003 6 when t=20 s, while, when the frequencies are nonidentical to each other, the difference between the maximum and the minimum frequencies of each oscillator can even reach 4.066×10-5 when t=0.3 s. The numerical simulations further verify the correctness of the theoretical results.
    Related Articles | Metrics

    Research on the spread of population-classified infectious diseases in scale-free networks

    2023, 37 (1):  273-279. 
    Abstract ( 104 )   PDF (2517KB) ( 164 )   Save
    In order to explore the law of the spread of infectious diseases in social networks and further accurately prevent and control the epidemic, this paper establishes a SIRS infectious disease model based on the scale-free network of households. Combined with the location of the center point and the structural hole point, the law of the spread of infectious diseases is analyzed. Through the quantitative study and numerical simulation of model parameters, the influence of infection rate, recovery rate and immune number on the spread of infectious diseases is obtained. The results show that the current prevention and control measures in China are timely and effective. At the same time, it is found that the control of the movement of specific populations and advance immunization can effectively achieve precise prevention and control of the epidemic, which provides a theoretical basis for the formulation of effective prevention and control strategies for infectious diseases.
    Related Articles | Metrics

    Research on economical driving of multi-mode hybrid electric vehicles facing urban traffic lights

    2023, 37 (1):  280-290. 
    Abstract ( 104 )   PDF (4605KB) ( 154 )   Save
    This paper takes a multi-mode hybrid electric vehicle (HEV) in an intelligent connected environment as the research object and researches economic driving for urban road traffic intersections. Firstly, the phase and timing data of the signal lights are obtained based on the information from the Internet to Vehicles, and a road network model of multiple signal intersections is built according to the constraints such as the position of the signal lights and the speed limit. Meanwhile, a control-oriented multi-mode hybrid powertrain component model and an energy consumption model for assembled cars are established. Secondly, economical driving of a single vehicle is solved based on the Pontryagin minimum principle (PMP). The scenario analysis of the traffic light intersections is performed, the effective speed range of the vehicle without stopping is planned, and the economical speed optimization of continuous signal intersections is analyzed. Finally, the optimal energy management strategy (EMS) for the multi-mode hybrid electric vehicle is solved based on model predictive control (MPC), and the penalty term about mode switching is introduced to improve the smoothness of the multi-mode hybrid power system. Compared with the dynamic programming-based energy management which belongs to the global optimum, the proposed control strategy achieves a near-optimal fuel economy of 3.767 L/100 km.
    Related Articles | Metrics

    Research on HAR-SMFV model and its prediction from the multi-fractal perspective

    2023, 37 (1):  291-301. 
    Abstract ( 82 )   PDF (1730KB) ( 103 )   Save
    Considering the multi-fractal, time-varying and heteroscedasticity of daytime volatility, this paper constructs HAR-HV, HAR-FV, HAR-BSMFV and HAR-TSMFV models and evaluates and compares the goodness of fit and prediction accuracy of these four HAR models. The empirical results and the MCS test confirm that the HAR-SMFV models with Markov-switching multi-fractal volatility have significantly improved predictive abilities and the results are robust. Among them, the HAR-TSMFV model not only describes the time-varying and heteroscedasticity of daytime volatility, but also captures the conversion between the three multi-fractal volatility forms, showing the highest prediction accuracy.
    Related Articles | Metrics

    Research on the hybrid fault diagnosis of alternating group graphs

    2023, 37 (1):  302-308. 
    Abstract ( 86 )   PDF (1259KB) ( 68 )   Save
    To measure the fault diagnosis capability of the multiprocessor system with alternating group graphs as topological structures under a hybrid faulty circumstance, this paper investigates the h-restricted vertex diagnosability and the r-restricted edge diagnosability of the alternating group graphs under the HPMC model. The relationship between the two kinds of hybrid fault diagnosability is obtained by their properties. Considering that the adjacent vertices in the alternating group graphs have common adjacent points, h and r are divided into different ranges. By contradiction, it is obtained that the h-restricted vertex diagnosability is 2n-h-4 for a range of 1≤h≤2n-7 of the alternating group graphs. Then, based on the relationship between the h-restricted vertex diagnosability and the r-restricted edge diagnosability, the r-restricted edge diagnosability is determined to be 2n-r-4 for a range of 3≤r≤2n-5 of the alternating group graphs. In addition, by constructing distinct consistent faulty pairs and proving that they are indistinguishable, the h-restricted vertex diagnosability of the alternating group graphs are determined to be 1, 0, 0 for h=2n-6, 2n-5, 2n-4, respectively, and the r-restricted edge diagnosability of the alternating group graphs are determined to be 2n-6, 2n-7 for r=1, 2, respectively. These results show the maximum number of the faulty elements that can be self-identified by the alternating group graphs under the hybrid faulty circumstance, reflecting the maximum fault diagnosis capability of the systems.
    Related Articles | Metrics

    An optimal algorithm for the minimum connected dominating set problem of interval graphs

    2023, 37 (1):  309-314. 
    Abstract ( 95 )   PDF (1225KB) ( 191 )   Save
    A simple linear algorithm is designed for the minimum connected dominating set problem of interval graphs. The time and space complexity of the algorithm is analyzed, and the feasibility and effectiveness of the algorithm are verified by cases and theory. The results show that the algorithm is linear, that is, a minimum connected dominating set found on the interval graph in O (m+n) time.
    Related Articles | Metrics
    “23rd International Conference of Fluid Power and Mechatronic Control Engineering” Special Column

    Buckling analysis of spherical tanks based on measured pillar offset

    2023, 37 (1):  315-321. 
    Abstract ( 79 )   PDF (3319KB) ( 93 )   Save
    In this study, a 5 000 m3 in-service propane spherical tank is selected as the research object, and the finite element models of circumferential offset and radial offset of the bottom of a single pillar are established respectively. Through the buckling response analysis carried out on the ANSYS Workbench platform, the limit values under the circumferential offset and the radial offset are obtained, and the buckling deformation law of the spherical tank under the pillar offset is studied. On this basis, the buckling analysis of the spherical tank is carried out according to the measured offset data of the pillar. It is found that there is no buckling in the radial outer offset of the bottom of the pillar within the studied offset range. The limit value of the radial inner offset of the bottom of the pillar is larger than that of the bottom circumferential offset, and the buckling deformation of the radial inner offset of the bottom of the pillar is smaller than that of the bottom circumferential offset. It shows that the bottom of the spherical tank pillar is easier to buckle when it is offset in the circumferential direction, and it is the most difficult to buckle when it is offset radially outside the bottom of the pillar. The position of the maximum buckling deformation of the spherical tank is at the tie rod, and the buckling response of the spherical tank under the radial inner offset and circumferential offset at the bottom of the pillar conforms to the characteristics of branch buckling.
    Related Articles | Metrics

    Structural design and optimization of a fluid-driven pipeline inspection robot

    2023, 37 (1):  322-329. 
    Abstract ( 112 )   PDF (2191KB) ( 153 )   Save
    In order to solve the problem of locating the leak point in a long-distance pipeline in service with a small diameter, this paper designs a fluid-driven pipeline inspection robot covered with a plastic sealing layer made of flexible materials. The relationship between the pressure difference needed to push the robot and the detection speed is analyzed by judging and locating the leak point through the changes of the flow pressure and the inner pipe diameter. Under the condition of the minimum pressure difference, this paper presents a structure design of a fluid-driven pipe robot based on a certain fluid density. The extrusion force of the pipeline on the robot proves to be the maximum pressure difference source second to fluid itself. The friction coefficient is measured, and the pressure of the robot is obtained by simulation experiments. Based on this, the response surface method is used to optimize the design of the robot. After the optimization design, both the maximum extrusion force and the pressure difference at the front and back of the robot in the pipeline reduce by 98.42%, and the average speed increases by 7.1%. The experimental results show that the robot can completely achieve suspension balance in this long-distance pipeline, thus minimizing the impact of friction, improving the detection speed and shortening the detection time. The external structure of the plastic sealing layer is designed by using double cone angle support, which can make the robot move forward and detect the leakage point in the pipeline under the action of small pressure difference.
    Related Articles | Metrics

    Research on the fuzzy PID-controlled speed of a valve controlled motor of a 10 MN hydraulic press

    2023, 37 (1):  330-336. 
    Abstract ( 124 )   PDF (2750KB) ( 125 )   Save
    This paper proposes a 10 MN hydraulic press driven by a hydraulic motor. In order to study the dynamic characteristics of the hydraulic press, the speed control system of the electro-hydraulic servo proportional valve-controlled hydraulic motor is used as the research object. By using the unique functional advantages of AMESim and Matlab/Simulink, this paper builds a mechanical model and a control model of the electro-hydraulic servo proportional valve-controlled motor system, and then carries out co-simulation. The fuzzy PID control algorithm is adopted in this paper to control the speed of the hydraulic motor and is compared with the traditional PID control algorithm. The simulation results show that the response time of the fuzzy PID control algorithm is significantly shorter than that of the conventional PID control strategy in the speed control of the electro-hydraulic servo proportional valve-controlled motor, with smaller overshoot and better tracking performance, and the control effect is significantly better than that of the conventional PID control strategy.
    Related Articles | Metrics

    Performance simulation analysis of 2.5D braided composite gears

    2023, 37 (1):  337-344. 
    Abstract ( 89 )   PDF (4461KB) ( 161 )   Save
    A three-dimensional angle interlock (2.5D) is a new structural composite material, which not only has the advantages of high specific strength, specific modulus, delamination resistance and impact damage resistance, but also overcomes the shortcomings of other three-dimensional multi-directional braided composites in the production of complex special-shaped structures. In this paper, based on the construction of a 2.5D shallow cross-bending coupled cell model and the analysis of mechanical properties, it is applied to a pair of cylindrical spur gears to meet the requirements of high strength and weight reduction. The static and kinematic analysis models of gears are established, and the gear optimization design is realized by finite element analysis. The static and dynamic meshing processes are analyzed, and the results describe the changes of contact strength and bending strength during meshing in detail, which provides reference for weight reduction and meshing characteristics analysis of 2.5D braided composite gears.
    Related Articles | Metrics

    Research on the in-pipe hydraulic rounding mechanism control based on the optimized fuzzy-PID genetic algorithm

    2023, 37 (1):  345-360. 
    Abstract ( 84 )   PDF (2895KB) ( 97 )   Save
    The ovality of pipe fittings has a huge impact on welding quality and efficiency, and also affects the residual stress distribution of the pipe fittings, thus affecting the service life. Therefore, it is necessary to design an integrated in-pipe rounding mechanism that is compact and suitable for a certain size range. Based on this, this paper proposes an in-pipe hydraulic rounding mechanism. In order to improve the control accuracy of the in-pipe hydraulic rounding system, the genetic algorithm is used to optimize the fuzzy-PID control method. Because simultaneous movement of multiple cylinders is required in the rounding process, the error compensation synchronous control method is adopted. The simulation results show that, compared with the traditional PID and ordinary fuzzy-PID control methods, the optimized fuzzy-PID controller has a faster response speed, smaller overshoot, more accurate and rapid control of the position of the roller, and the error is controlled in the range from 0.1% to 0.2%. Inside, the multi-cylinder synchronous motion has a fast response speed and precise control, which can realize the precise rounding of the pipeline. This fuzzy-PID hydraulic rounding mechanism improves the rounding quality and provides a new idea for the design of the in-pipe rounding mechanism.
    Related Articles | Metrics