Abstract
The integrated navigation system is used to estimate the position, velocity, and attitude of a vehicle with the output of inertial sensors. This paper concentrates on the problem of the INS/GPS integrated navigation system design and simulation. The structure of the INS/GPS integrated navigation system is made up of four parts: 1) GPS receiver, 2) Inertial Navigation System, 3) Extended Kalman filter, and 4) Integrated navigation scheme. Afterwards, we illustrate how to simulate the integrated navigation system with the extended Kalman filter by measuring position, velocity and attitude. Particularly, the extended Kalman filter can estimate states of the nonlinear system in the noisy environment. In extended Kalman filter, the estimation of the state vector and the error covariance matrix are computed by steps: 1) time update and 2) measurement update. Finally, the simulation process is implemented by Matlab, and simulation results prove that the error rate of statement measuring is lower when applying the extended Kalman filter in the INS/GPS integrated navigation system.
1 Introduction
Early navigation theory was used to handle ships sailing on the ocean, however, navigation technology has penetrated into every conceivable a vehicle in recent years, including land search, remote tracking, ship management, traffic management and other services [1, 2]. The navigation technology is used to guide an object from one point to another point [3]. Navigation system platforms are able to measure instantaneous velocity, direction, position and posture, and then provides this information to the operator and then provides proper guidance to the carrier [4, 5].
With the rapid progress and development of technology, more and more information can be exploited in the navigation system, and navigation methods have been updated frequently. Apart from traditional inertial navigation systems, (such as satellite navigation system, doppler navigation systems, ground-based radio navigation system, and so on) there are many new navigation systems, such as the celestial navigation system, the geomagnetic navigation system, the scene matching system, the terrain matching system, and the visual navigation system [6].
As is well known that, the INS/GPS navigation system has been widely used in integrated navigation system. Inertial Navigation System (denoted as INS) refers to a system which can compute the position, velocity, and attitude of a device with the output of inertial sensors [7]. Particularly, the measurements of the inertial sensors include errors because of physical limitations. However, errors may be accumulated in the navigation scheme of INS [8]. On the other hand, Global Positioning System (named as GPS) is often utilized as an aiding sensor in INS. Therefore, the INS/GPS integrated system has been widely exploited in several navigation fields. Unfortunately, there are many drawbacks in GPS, such as low sampling rate [9, 10]. To solve this proposed problem, in this paper, we focus on the INS/GPS Integrated Navigation System simulation.
Innovations of this paper lie in the following aspects:
The extended Kalman filter is used to estimate states of the nonlinear system in the noisy environment.
In the extended Kalman filter, the estimation of the state vector and the error covariance matrix are obtained by a time update process and a measurement update process.
In recent years, the rapid development of computer technology has encouraged the development of Kalman filtering model, and Kalman filtering has been successfully used in the integrated navigation system. To solve the problem in standard Kalman filtering, the extended Kalman filter is introduced in this paper. The rest of the paper is organized as follows. Section 2 illustrates related works about the extended Kalman filter. In section 3, we discuss how to design the INS/GPS integrated navigation system. Section 4 proposes the method to simulate the integrated navigation system using the Extended Kalman Filter. In section 5, experimental simulation is given the test the performance of the proposed method. Finally, the whole paper is concluded in Section 6.
2 Related works
The basic function of navigation is to provide real-time status information for the carrier. Due to system noises and measurement noises, how to extract the real states of the information from the noise navigation environment should be solved. Furthermore, the key issue in integrated navigation system is the fusion filtering. In order to effectively model the nonlinear systems, the extended Kalman filter (EKF) has been proposed and widely used.
The core idea of the extended Kalman filter is to approximate nonlinear model by iterative filtering with a linearized method used in EKF is by using the nonlinear Taylor expansion which ignores the rest of the higher order terms. The extended Kalman filter has been exploited in nonlinear filtering application, such as aerospace, navigation, target tracking, and so on. Related works on the extended Kalman filter are listed as follows.
Delgado et al. proposed a model-based method to detect and isolate non-concurrent multiple leaks in a pipeline, and pressure and flow sensors are located at the pipeline ends. Particularly, the proposed method depends on a nonlinear modelling derived from Water-Hammer equations, and the Extended Kalman Filters are exploited to calculate leak coefficients [11].
Bukhari et al. proposed a real-time algorithm to forecast respiratory motion in 3D space and realizing a gating function without pre-specifying a particular phase of the patient’s breathing cycle. The proposed method utilize an extended Kalman filter independently along each coordinate to forecast the respiratory motion and then exploits a Gaussian process regression network to revise the prediction error of the EKF in 3D space [12].
Miljkovic et al. used the EKF coupled with a feedforward neural network for the simultaneous localization and mapping. The main innovations of this paper lie in that the neural extended Kalman filter is used online to estimate an error between the motion model of the mobile robot and the real system performance [13].
Zareian et al. proposed an appropriate approach for computing road friction coefficient. The proposed algorithm utilized measured values from wheel angular velocity and yaw rate sensors of a vehicle. Particularly, vehicle lateral and longitudinal velocities along with yaw rate value are obtained by the extended Kalman filter. Afterwards, lateral and longitudinal tidal forces are calculated with a recursive least square algorithm [14].
Liu et al. combined the Minimum Model Error criterion with the Extended Kalman Filter to estimate states of 4WD vehicle states. Moreover, this paper constructed a general 5-input 3-output and 3 states estimation system, which utilized both the arbitrary nonlinear model error and the white Gauss measurement noise [15].
Apart from the above works, the extended Kalman Filter has been utilized in other fields, such as hemodynamic state estimation [16], Acoustic velocity measurement [17], Proton Exchange Membrane Fuel Cell [18], structural parameters estimation [19], and Radar Tracking [20]. In this paper, we try to introduce the extended Kalman Filter to estimate the states of the INS/GPS integrated navigation system.
3 Overview of the INS/GPS integrated navigation system
Inertial Navigation System (INS) refers to a system which can compute the position, velocity, and attitude using inertial sensors. The measurements of the inertial sensors may include errors because of its design limitations, and the errors are accumulated in the navigation process. Hence, if the error is not compensated with other types of sensors, the information of INS can be used in a short time. Currently, the Global Positioning System (GPS) can provide helpful information for INS. On the other hand, GPS also has some disadvantages, such as low sampling rate and satellite signal loosing. Structure of the INS/GPS integrated navigation system is shown in Figure 1.

Structure of the INS/GPS integrated navigation system
As is shown in Figure1, INS system obtains inputs from the gyros and accelerometers, and a state vector is defined as follows.
where parameters ϕE, ϕN, ϕU represent errors of the platform misalignment respectively, and δVE, δVN, δVU refer to the velocity errors respectively. Furthermore, δL,δλ, δh denote position errors of latitude, longitude and altitude respectively. Based on the definition of state vector, the error state at time t is represented as follows.
where W (t) is the model vector, and it is computed by the following equation.
where εE, εN, εU refer to the errors of gyros drift, ∇E, ∇N, ∇U denote the errors of accelerometer, and symbol E, N, U refer to East, North and Up direction in the geographical frame respectively. Particularly, matrix A is generated from the error equations of INS system, and G is the error transition matrix. Integrating the position information and velocity information together, and the measurement equation to represent the observation of the integrated navigation system is described as follows.
where δ L, δ λ, δ λ mean the errors in latitude, longitude and height respectively, and δvE, δ vN refer to the errors with the INS velocities
H denotes a measurement matrix and V refers to the measurement errors. Afterwards, the INS/GPS integrated navigation system can be described the following discretely transforming process.
4 Integrated navigation system simulation based on the extended Kalman filter
In this section, we discuss how to simulate the Integrated Navigation System using the Extended Kalman Filter by measuring position, velocity and attitude. The Kalman filter is used to estimate states of dynamic systems by a stochastic linear state-space model as follows [21–23].
The above equation refers to that the continuous state to control system dynamics.
where this equation denotes the discrete measurement which is corresponding to the system X (t) to the available measurements Yk. Moreover, u (t) is the model input, W (t) is the Gaussian process noise, and Vk is the measurement noises.
Suppose that a time point is represented as tk = k ⋅ Ts, where Ts refers to a sampling period. The estimation of the state vector
In the time update process, we utilize a priori to calculate the state
where Φ means the state transition matrix. In the measurement update process, the state
As is illustrated in the above, we can see that the Kalman Filter refers to an optimal estimator which recursively couples the most recent measurements into the linear model to update the model states. However, the Kalman Filter can only measure states of the systems, in which the dynamic and observation functions are linear [24]. To solve the problem of the INS/GPS integrated navigation system which is belonged to a nonlinear system measuring, an extended Kalman Filter are utilized in this paper.
An extended Kalman filter is able to estimate system state in the noisy environment [25]. Predicted state estimate
where F() refers to the Jacobian matrix of f, and it is calculated as follows.
Afterwards, the following equations represent the measurement update process:
where H denotes the Jacobian matrix of h, and it is computed as follows.
We simulate the integrated navigation system based on the extended Kalman filter using Matlab, and the calculation procedure is listed as follows.
Step 1: Suppose that we have X (0) and P (0)
Step 2: Predicting the values of
Step 3: Computing the coefficient Φk,k − 1 and Hk
Step 4: Computing the Pk,k − 1
Step 5: Computing the extended Kalman gain Kk
Step 6: Estimating the values:
Step 7: K++
Step 8: Go to Step 2.
5 Experimental simulation
According to the mathematical model the INS/GPS integrated navigation system discussed in the above chapter, and we utilize the northeast sky coordinates in this simulation. Particularly, longitude, latitude, speed at east direction, speed at north direction and Euler angle are used as state variables in the system simulation process. We exploit the extended Kalman filtering to estimate system states.
We suppose carrier flies horizontally along the equatorial eastward direction, and flight simulation parameters are set as follows: 1) initial position is located at 50 degrees North latitude and 110 degrees East longitude, 2) the height is set to 5000 m, 3) the initial rate is set to 170 m/s (for the East direction), and 0 m/s (for the North direction), 4) the initial error of the longitude and latitude are set to 50 m respectively, 5) the initial velocity error is 0.5 m/s, 6) platform Euler angle error is 0.12′, 7) the Gyro first order Markoff shift is 0.1°/h, 8) the first order Markov Kraft accelerometer bias is 10-3 g, and 9) sampled emulation interval and simulation time are set to 1 s and 600 s respectively.
The simulation process is implemented by Matlab, and then the extended Kalman filter is utilized to test the performance of filter divergence suppression and the wide range of adaptive capacity. Furthermore, we maintain the initial model unchanged in 0 s to 100 s. From 101 s to 200 s, measurement noises become five times and seven times as much as the initial value in the time range [101s,200s] and [201s,400s] respectively. Particularly, the experiments are developed using the MATLAB 7.0.1 simulation environment.
Afterwards, the measurement noises restore to its original value after 401 s. Initial state settings for filter are described in Table 1.
Initial state settings for filter
| Initial state | value | |
|---|---|---|
| Position error | longitude | 110°E |
| latitude | 50°N | |
| height | 5000 m | |
| Gyroscope | Zero offset | 5 (°/h) |
| Random value | 1⋅10− 2(°/h) | |
| Accelerometer | Zero offset | 3⋅10− 5g0 |
| Random value | 2⋅10− 5g0 | |
Afterwards, indicators of the system measurement noise variance are listed in Table 2.
Indicators of the system measurement noise variance
| Noise mean square deviation | Value | |
|---|---|---|
| Gyro white noise drift | 3(°/h) | |
| Accelerometer white noise drift | 0.001m/s2 | |
| Receiver | Precision of pseudo range | 2.0m (1σ) |
| technical | measurement | |
| index | Measurement accuracy of | 0.1m/s |
| Pseudo range rate | (1σ) | |
| Computation | Inertial measurement data | 0.001s |
| period | update cycle | |
| Satellite receiver data | 0.1s | |
| update cycle | ||
| Navigation computing cycle | 0.1s | |
Based on the above simulation environment, we utilize the extended Kalman filter to measure parameters of the INS/GPS integrated navigation system. Experimental results are shown in Figure 2 to Figure 8.

Platform error of the east orientation using the extended Kalman filter

Platform error of the north orientation using the extended Kalman filter

Platform error of the up orientation using the extended Kalman filter

Speed error of the east orientation using the extended Kalman filter

Speed error of the north orientation using the extended Kalman filter

Error of latitude using the extended Kalman filter

Error of longitude using the extended Kalman filter
From the experimental results, it can be observed that using the extended Kalman filter in integrated navigation system, the error rate of statement measuring is very low. The standard Kalman filter is very sensitive to the unexpected external perturbations, measurement accuracy is not satisfied by us. On the contrary, we can see that the extended Kalman filter performs robustly and can effective reduce the measurement error rate. Furthermore, from the simulation results, we find that 1) the extended Kalman filter is more stable in anti filter divergence without external calibration, and 2) the extended Kalman filter achieves a better performance for the unexpected perturbation. The reason why our algorithm performs better than other methods lies in that 1) a Kalman filter is used to estimate states of dynamic systems by a stochastic linear state-space model, and 2) we define the state vector and the error covariance matrix to help construct an integrated navigation system, and the above two matrices are computed by two processes: a) Time update and b) measurement update.
6 Conclusion
In this paper, we aims to design and simulate the INS/GPS integrated navigation system, and the main works are to estimate the position, velocity, and attitude of a vehicle with the output of inertial sensors. Firstly, the structure of the INS/GPS integrated navigation system is given. Afterwards, we proposed a novel method to simulate the integrated navigation system with the extended Kalman filter by measuring position, velocity and attitude. In the end, simulation results demonstrate that the extended Kalman filter performs stably in anti filter divergence without external calibration, and performs better than a Kalman filter for the unexpected perturbation.
To extend this work, in the future, we will try to use other initial state settings for filter to test the adaptability of the proposed design.
References
[1] Batista P., Silvestre C., Oliveira P., Tightly coupled long baseline/ultra-short baseline integrated navigation system, Int J Syst Sci, 2016, 47, 1837-1855.10.1080/00207721.2014.955070Search in Google Scholar
[2] Kong X.Z., Duan X.G., Wang Y.G., An integrated system for planning, navigation and robotic assistance for mandible reconstruction surgery, Intell Serv Robot, 2016, 9, 113-121.10.1007/s11370-015-0189-7Search in Google Scholar
[3] Yang S.J., Yang G.L., Zhu Z.L., Li J., Stellar Refraction-Based SINS/CNS Integrated Navigation System for Aerospace Vehicles, J Aerospace Eng, 2016, 29, 25-34.10.1061/(ASCE)AS.1943-5525.0000536Search in Google Scholar
[4] Yun S.C., Lee Y.J., Sung S.K., Range/Optical Flow-aided Integrated Navigation System in a Strapdown Sensor Configuration, Int J Control Autom, 2016, 14, 229-241.10.1007/s12555-014-0336-5Search in Google Scholar
[5] Sasani S., Asgari J., Amiri-Simkooei A.R., Improving MEMS-IMU/GPS integrated systems for land vehicle navigation applications, GPS Solut, 2016, 20, 89-100.10.1007/s10291-015-0471-3Search in Google Scholar
[6] Zhang L., Xiong Z., Lai J.Z., Liu J.Y., Optical flow-aided navigation for UAV: A novel information fusion of integrated MEMS navigation system, OPTIK, 2016, 127, 447-451.10.1016/j.ijleo.2015.10.092Search in Google Scholar
[7] Liu Y.T., Xu X.S., Liu X.X., Zhang T., Li Y., Yao Y.Q., Wu L., Tong J.W., A Fast Gradual Fault Detection Method for Underwater Integrated Navigation Systems, J Navigation, 2016, 69, 93-112.10.1017/S0373463315000430Search in Google Scholar
[8] Perera L.P., Guedes S.C., Collision risk detection and quantification in ship navigation with integrated bridge systems, Ocean Eng, 2015, 109, 344-354.10.1016/j.oceaneng.2015.08.016Search in Google Scholar
[9] Wang Q.Y., Diao M., Gao W., Zhu M.H., Xiao S., Integrated navigation method of a marine strapdown inertial navigation system using a star sensor, Meas Sci Tech, 2015, 26, 6-75.10.1088/0957-0233/26/11/115101Search in Google Scholar
[10] Hu S.X., Xu S.K., Wang D.H., Zhang A.W., Optimization Algorithm for Kalman Filter Exploiting the Numerical Characteristics of SINS/GPS Integrated Navigation Systems, Sensors, 2015, 15, 28402-28420.10.3390/s151128402Search in Google Scholar PubMed PubMed Central
[11] Delgado-Aguinaga J.A., Besancon G. Begovich O., Carvajal J.E., Multi-leak diagnosis in pipelines based on Extended Kalman Filter, Control Eng Pract, 2016, 49, 139-148.10.1016/j.conengprac.2015.10.008Search in Google Scholar
[12] Bukhari W., Hong S.M., Real-time prediction and gating of respiratory motion in 3D space using extended Kalman filters and Gaussian process regression network, Phys Med Biol, 2016, 61, 1947-1967.10.1088/0031-9155/61/5/1947Search in Google Scholar PubMed
[13] Miljkovic Z., Vukovic N., Mitic M., Neural extended Kalman filter for monocular SLAM in indoor environment, P I Mech Eng C-J Mec, 2016, 230, 856-866.10.1177/0954406215586589Search in Google Scholar
[14] Zareian A., Azadi S., Kazemi R., Estimation of road friction coefficient using extended Kalman filter, recursive least square, and neural network, P I Mech Eng K-J Mul, 2016, 230, 52-68.10.1177/1464419315573353Search in Google Scholar
[15] Liu W., He H.W., Sun F.C., Vehicle state estimation based on Minimum Model Error criterion combining with Extended Kalman Filter, J Franklin I S, 2016, 353, 834-856.10.1016/j.jfranklin.2016.01.005Search in Google Scholar
[16] Aslan S., Comparison of the hemodynamic filtering methods and particle filter with extended Kalman filter approximated proposal function as an efficient hemodynamic state estimation method, Biomed Signal Proces, 2016, 25, 99-107.10.1016/j.bspc.2015.10.003Search in Google Scholar
[17] Le D.A., Plantier G., Valiere J.C., Gazengel B., Acoustic velocity measurement by means of Laser Doppler Velocimetry: Development of an Extended Kalman Filter and validation in free-field measurement, Mech Syst Signal PR, 2016, 70-71, 832-852.10.1016/j.ymssp.2015.08.020Search in Google Scholar
[18] Bressel M., Hilairet M., Hissel D., Bouamama B.O., Extended Kalman Filter for prognostic of Proton Exchange Membrane Fuel Cell, Appl Energ, 2016, 164, 220-227.10.1016/j.apenergy.2015.11.071Search in Google Scholar
[19] Pan S.W., Xiao D., Xing S.T., Law S.S., Du P.Y., Li Y.J., A general extended Kalman filter for simultaneous estimation of system and unknown inputs, Eng Struct, 2016, 109, 85-98.10.1016/j.engstruct.2015.11.014Search in Google Scholar
[20] Kulikov G.Y., Kulikova M. V., The Accurate Continuous-Discrete, Extended Kalman Filter for Radar Tracking, IEEE T Signal Proces, 2016, 64, 948-958.10.1109/TSP.2015.2493985Search in Google Scholar
[21] Wang Y.W., Binaud N., Gogu C., Bes C., Fu J., Determination of Paris’ law constants and crack length evolution via Extended and Unscented Kalman filter: An application to aircraft fuselage panels, Mech Syst Signal Pr, 2016, 80, 262-281.10.1016/j.ymssp.2016.04.027Search in Google Scholar
[22] Zhang S., Zhao J.H., Zhao Y., Li G.L., Gain-Constrained Extended Kalman Filtering with Stochastic Nonlinearities and Randomly Occurring Measurement Delays, Circ Syst Signal Pr, 2016, 35, 3957-3980.10.1007/s00034-016-0244-4Search in Google Scholar
[23] Peng X.J., Cai Y., Li Q., Wang K., Comparison of reactivity estimation performance between two extended Kalman filtering schemes, Ann Nucl Energy, 2016, 96, 76-82.10.1016/j.anucene.2016.05.026Search in Google Scholar
[24] Li B., You N., Research on the Dynamic Evolution Behavior of Group Loitering Air Vehicles, Appl Math Nonl Sci, 2016, 1, 353-358.10.21042/AMNS.2016.2.00030Search in Google Scholar
[25] Vishwanath B. Awati S.N., Mahesh K. N., Multigrid method for the solution of EHL line contact with bio-based oils as lubricants, Appl Math Nonl Sci, 2016, 1, 359-368.10.21042/AMNS.2016.2.00031Search in Google Scholar
© 2017 W. Zhou et al.
This work is licensed under the Creative Commons Attribution-NonCommercial-NoDerivatives 3.0 License.
Articles in the same Issue
- Regular Articles
- Analysis of a New Fractional Model for Damped Bergers’ Equation
- Regular Articles
- Optimal homotopy perturbation method for nonlinear differential equations governing MHD Jeffery-Hamel flow with heat transfer problem
- Regular Articles
- Semi- analytic numerical method for solution of time-space fractional heat and wave type equations with variable coefficients
- Regular Articles
- Investigation of a curve using Frenet frame in the lightlike cone
- Regular Articles
- Construction of complex networks from time series based on the cross correlation interval
- Regular Articles
- Nonlinear Schrödinger approach to European option pricing
- Regular Articles
- A modified cubic B-spline differential quadrature method for three-dimensional non-linear diffusion equations
- Regular Articles
- A new miniaturized negative-index meta-atom for tri-band applications
- Regular Articles
- Seismic stability of the survey areas of potential sites for the deep geological repository of the spent nuclear fuel
- Regular Articles
- Distributed containment control of heterogeneous fractional-order multi-agent systems with communication delays
- Regular Articles
- Sensitivity analysis and economic optimization studies of inverted five-spot gas cycling in gas condensate reservoir
- Regular Articles
- Quantum mechanics with geometric constraints of Friedmann type
- Regular Articles
- Modeling and Simulation for an 8 kW Three-Phase Grid-Connected Photo-Voltaic Power System
- Regular Articles
- Application of the optimal homotopy asymptotic method to nonlinear Bingham fluid dampers
- Regular Articles
- Analysis of Drude model using fractional derivatives without singular kernels
- Regular Articles
- An unsteady MHD Maxwell nanofluid flow with convective boundary conditions using spectral local linearization method
- Regular Articles
- New analytical solutions for conformable fractional PDEs arising in mathematical physics by exp-function method
- Regular Articles
- Quantum mechanical calculation of electron spin
- Regular Articles
- CO2 capture by polymeric membranes composed of hyper-branched polymers with dense poly(oxyethylene) comb and poly(amidoamine)
- Regular Articles
- Chain on a cone
- Regular Articles
- Multi-task feature learning by using trace norm regularization
- Regular Articles
- Superluminal tunneling of a relativistic half-integer spin particle through a potential barrier
- Regular Articles
- Neutrosophic triplet normed space
- Regular Articles
- Lie algebraic discussion for affinity based information diffusion in social networks
- Regular Articles
- Radiation dose and cancer risk estimates in helical CT for pulmonary tuberculosis infections
- Regular Articles
- A comparison study of steady-state vibrations with single fractional-order and distributed-order derivatives
- Regular Articles
- Some new remarks on MHD Jeffery-Hamel fluid flow problem
- Regular Articles
- Numerical investigation of magnetohydrodynamic slip flow of power-law nanofluid with temperature dependent viscosity and thermal conductivity over a permeable surface
- Regular Articles
- Charge conservation in a gravitational field in the scalar ether theory
- Regular Articles
- Measurement problem and local hidden variables with entangled photons
- Regular Articles
- Compression of hyper-spectral images using an accelerated nonnegative tensor decomposition
- Regular Articles
- Fabrication and application of coaxial polyvinyl alcohol/chitosan nanofiber membranes
- Regular Articles
- Calculating degree-based topological indices of dominating David derived networks
- Regular Articles
- The structure and conductivity of polyelectrolyte based on MEH-PPV and potassium iodide (KI) for dye-sensitized solar cells
- Regular Articles
- Chiral symmetry restoration and the critical end point in QCD
- Regular Articles
- Numerical solution for fractional Bratu’s initial value problem
- Regular Articles
- Structure and optical properties of TiO2 thin films deposited by ALD method
- Regular Articles
- Quadruple multi-wavelength conversion for access network scalability based on cross-phase modulation in an SOA-MZI
- Regular Articles
- Application of ANNs approach for wave-like and heat-like equations
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Study on node importance evaluation of the high-speed passenger traffic complex network based on the Structural Hole Theory
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A mathematical/physics model to measure the role of information and communication technology in some economies: the Chinese case
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Numerical modeling of the thermoelectric cooler with a complementary equation for heat circulation in air gaps
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- On the libration collinear points in the restricted three – body problem
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on Critical Nodes Algorithm in Social Complex Networks
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A simulation based research on chance constrained programming in robust facility location problem
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A mathematical/physics carbon emission reduction strategy for building supply chain network based on carbon tax policy
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Mathematical analysis of the impact mechanism of information platform on agro-product supply chain and agro-product competitiveness
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A real negative selection algorithm with evolutionary preference for anomaly detection
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A privacy-preserving parallel and homomorphic encryption scheme
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Random walk-based similarity measure method for patterns in complex object
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A Mathematical Study of Accessibility and Cohesion Degree in a High-Speed Rail Station Connected to an Urban Bus Transport Network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Design and Simulation of the Integrated Navigation System based on Extended Kalman Filter
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Oil exploration oriented multi-sensor image fusion algorithm
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Analysis of Product Distribution Strategy in Digital Publishing Industry Based on Game-Theory
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Expanded Study on the accumulation effect of tourism under the constraint of structure
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Unstructured P2P Network Load Balance Strategy Based on Multilevel Partitioning of Hypergraph
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on the method of information system risk state estimation based on clustering particle filter
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Demand forecasting and information platform in tourism
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Physical-chemical properties studying of molecular structures via topological index calculating
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Local kernel nonparametric discriminant analysis for adaptive extraction of complex structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- City traffic flow breakdown prediction based on fuzzy rough set
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Conservation laws for a strongly damped wave equation
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Blending type approximation by Stancu-Kantorovich operators based on Pólya-Eggenberger distribution
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Computing the Ediz eccentric connectivity index of discrete dynamic structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A discrete epidemic model for bovine Babesiosis disease and tick populations
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Study on maintaining formations during satellite formation flying based on SDRE and LQR
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Relationship between solitary pulmonary nodule lung cancer and CT image features based on gradual clustering
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A novel fast target tracking method for UAV aerial image
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Fuzzy comprehensive evaluation model of interuniversity collaborative learning based on network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Conservation laws, classical symmetries and exact solutions of the generalized KdV-Burgers-Kuramoto equation
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- After notes on self-similarity exponent for fractal structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Excitation probability and effective temperature in the stationary regime of conductivity for Coulomb Glasses
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Comparisons of feature extraction algorithm based on unmanned aerial vehicle image
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on identification method of heavy vehicle rollover based on hidden Markov model
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Classifying BCI signals from novice users with extreme learning machine
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Topics on data transmission problem in software definition network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Statistical inferences with jointly type-II censored samples from two Pareto distributions
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Estimation for coefficient of variation of an extension of the exponential distribution under type-II censoring scheme
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Analysis on trust influencing factors and trust model from multiple perspectives of online Auction
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Coupling of two-phase flow in fractured-vuggy reservoir with filling medium
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Production decline type curves analysis of a finite conductivity fractured well in coalbed methane reservoirs
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Flow Characteristic and Heat Transfer for Non-Newtonian Nanofluid in Rectangular Microchannels with Teardrop Dimples/Protrusions
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- The size prediction of potential inclusions embedded in the sub-surface of fused silica by damage morphology
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Research on carbonate reservoir interwell connectivity based on a modified diffusivity filter model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- The method of the spatial locating of macroscopic throats based-on the inversion of dynamic interwell connectivity
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Unsteady mixed convection flow through a permeable stretching flat surface with partial slip effects through MHD nanofluid using spectral relaxation method
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- A volumetric ablation model of EPDM considering complex physicochemical process in porous structure of char layer
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Numerical simulation on ferrofluid flow in fractured porous media based on discrete-fracture model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Macroscopic lattice Boltzmann model for heat and moisture transfer process with phase transformation in unsaturated porous media during freezing process
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Modelling of intermittent microwave convective drying: parameter sensitivity
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Simulating gas-water relative permeabilities for nanoscale porous media with interfacial effects
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Simulation of counter-current imbibition in water-wet fractured reservoirs based on discrete-fracture model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Investigation effect of wettability and heterogeneity in water flooding and on microscopic residual oil distribution in tight sandstone cores with NMR technique
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Analytical modeling of coupled flow and geomechanics for vertical fractured well in tight gas reservoirs
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Special Issue: Ever New "Loopholes" in Bell’s Argument and Experimental Tests
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- The ultimate loophole in Bell’s theorem: The inequality is identically satisfied by data sets composed of ±1′s assuming merely that they exist
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Erratum to: The ultimate loophole in Bell’s theorem: The inequality is identically satisfied by data sets composed of ±1′s assuming merely that they exist
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Rhetoric, logic, and experiment in the quantum nonlocality debate
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- What If Quantum Theory Violates All Mathematics?
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Relativity, anomalies and objectivity loophole in recent tests of local realism
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- The photon identification loophole in EPRB experiments: computer models with single-wing selection
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Bohr against Bell: complementarity versus nonlocality
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Is Einsteinian no-signalling violated in Bell tests?
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Bell’s “Theorem”: loopholes vs. conceptual flaws
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Nonrecurrence and Bell-like inequalities
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Three-dimensional computer models of electrospinning systems
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Electric field computation and measurements in the electroporation of inhomogeneous samples
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Modelling of magnetostriction of transformer magnetic core for vibration analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Comparison of the fractional power motor with cores made of various magnetic materials
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Dynamics of the line-start reluctance motor with rotor made of SMC material
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Inhomogeneous dielectrics: conformal mapping and finite-element models
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Topology optimization of induction heating model using sequential linear programming based on move limit with adaptive relaxation
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of inter-turn short-circuit at start-up of induction machine based on torque analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Current superimposition variable flux reluctance motor with 8 salient poles
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Modelling axial vibration in windings of power transformers
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field analysis & eddy current losses calculation in five-phase tubular actuator
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Hybrid excited claw pole generator with skewed and non-skewed permanent magnets
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Electromagnetic phenomena analysis in brushless DC motor with speed control using PWM method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field-circuit analysis and measurements of a single-phase self-excited induction generator
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- A comparative analysis between classical and modified approach of description of the electrical machine windings by means of T0 method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field-based optimal-design of an electric motor: a new sensitivity formulation
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Application of the parametric proper generalized decomposition to the frequency-dependent calculation of the impedance of an AC line with rectangular conductors
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Virtual reality as a new trend in mechanical and electrical engineering education
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Holonomicity analysis of electromechanical systems
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- An accurate reactive power control study in virtual flux droop control
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Localized probability of improvement for kriging based multi-objective optimization
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Research of influence of open-winding faults on properties of brushless permanent magnets motor
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Optimal design of the rotor geometry of line-start permanent magnet synchronous motor using the bat algorithm
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Model of depositing layer on cylindrical surface produced by induction-assisted laser cladding process
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of inter-turn faults in transformer winding using the capacitor discharge method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- A novel hybrid genetic algorithm for optimal design of IPM machines for electric vehicle
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Lamination effects on a 3D model of the magnetic core of power transformers
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of vertical disparity in three-dimensional visualizations
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Calculations of magnetic field in dynamo sheets taking into account their texture
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- 3-dimensional computer model of electrospinning multicapillary unit used for electrostatic field analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Optimization of wearable microwave antenna with simplified electromagnetic model of the human body
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Induction heating process of ferromagnetic filled carbon nanotubes based on 3-D model
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Speed control of an induction motor by 6-switched 3-level inverter
Articles in the same Issue
- Regular Articles
- Analysis of a New Fractional Model for Damped Bergers’ Equation
- Regular Articles
- Optimal homotopy perturbation method for nonlinear differential equations governing MHD Jeffery-Hamel flow with heat transfer problem
- Regular Articles
- Semi- analytic numerical method for solution of time-space fractional heat and wave type equations with variable coefficients
- Regular Articles
- Investigation of a curve using Frenet frame in the lightlike cone
- Regular Articles
- Construction of complex networks from time series based on the cross correlation interval
- Regular Articles
- Nonlinear Schrödinger approach to European option pricing
- Regular Articles
- A modified cubic B-spline differential quadrature method for three-dimensional non-linear diffusion equations
- Regular Articles
- A new miniaturized negative-index meta-atom for tri-band applications
- Regular Articles
- Seismic stability of the survey areas of potential sites for the deep geological repository of the spent nuclear fuel
- Regular Articles
- Distributed containment control of heterogeneous fractional-order multi-agent systems with communication delays
- Regular Articles
- Sensitivity analysis and economic optimization studies of inverted five-spot gas cycling in gas condensate reservoir
- Regular Articles
- Quantum mechanics with geometric constraints of Friedmann type
- Regular Articles
- Modeling and Simulation for an 8 kW Three-Phase Grid-Connected Photo-Voltaic Power System
- Regular Articles
- Application of the optimal homotopy asymptotic method to nonlinear Bingham fluid dampers
- Regular Articles
- Analysis of Drude model using fractional derivatives without singular kernels
- Regular Articles
- An unsteady MHD Maxwell nanofluid flow with convective boundary conditions using spectral local linearization method
- Regular Articles
- New analytical solutions for conformable fractional PDEs arising in mathematical physics by exp-function method
- Regular Articles
- Quantum mechanical calculation of electron spin
- Regular Articles
- CO2 capture by polymeric membranes composed of hyper-branched polymers with dense poly(oxyethylene) comb and poly(amidoamine)
- Regular Articles
- Chain on a cone
- Regular Articles
- Multi-task feature learning by using trace norm regularization
- Regular Articles
- Superluminal tunneling of a relativistic half-integer spin particle through a potential barrier
- Regular Articles
- Neutrosophic triplet normed space
- Regular Articles
- Lie algebraic discussion for affinity based information diffusion in social networks
- Regular Articles
- Radiation dose and cancer risk estimates in helical CT for pulmonary tuberculosis infections
- Regular Articles
- A comparison study of steady-state vibrations with single fractional-order and distributed-order derivatives
- Regular Articles
- Some new remarks on MHD Jeffery-Hamel fluid flow problem
- Regular Articles
- Numerical investigation of magnetohydrodynamic slip flow of power-law nanofluid with temperature dependent viscosity and thermal conductivity over a permeable surface
- Regular Articles
- Charge conservation in a gravitational field in the scalar ether theory
- Regular Articles
- Measurement problem and local hidden variables with entangled photons
- Regular Articles
- Compression of hyper-spectral images using an accelerated nonnegative tensor decomposition
- Regular Articles
- Fabrication and application of coaxial polyvinyl alcohol/chitosan nanofiber membranes
- Regular Articles
- Calculating degree-based topological indices of dominating David derived networks
- Regular Articles
- The structure and conductivity of polyelectrolyte based on MEH-PPV and potassium iodide (KI) for dye-sensitized solar cells
- Regular Articles
- Chiral symmetry restoration and the critical end point in QCD
- Regular Articles
- Numerical solution for fractional Bratu’s initial value problem
- Regular Articles
- Structure and optical properties of TiO2 thin films deposited by ALD method
- Regular Articles
- Quadruple multi-wavelength conversion for access network scalability based on cross-phase modulation in an SOA-MZI
- Regular Articles
- Application of ANNs approach for wave-like and heat-like equations
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Study on node importance evaluation of the high-speed passenger traffic complex network based on the Structural Hole Theory
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A mathematical/physics model to measure the role of information and communication technology in some economies: the Chinese case
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Numerical modeling of the thermoelectric cooler with a complementary equation for heat circulation in air gaps
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- On the libration collinear points in the restricted three – body problem
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on Critical Nodes Algorithm in Social Complex Networks
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A simulation based research on chance constrained programming in robust facility location problem
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A mathematical/physics carbon emission reduction strategy for building supply chain network based on carbon tax policy
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Mathematical analysis of the impact mechanism of information platform on agro-product supply chain and agro-product competitiveness
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A real negative selection algorithm with evolutionary preference for anomaly detection
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A privacy-preserving parallel and homomorphic encryption scheme
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Random walk-based similarity measure method for patterns in complex object
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A Mathematical Study of Accessibility and Cohesion Degree in a High-Speed Rail Station Connected to an Urban Bus Transport Network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Design and Simulation of the Integrated Navigation System based on Extended Kalman Filter
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Oil exploration oriented multi-sensor image fusion algorithm
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Analysis of Product Distribution Strategy in Digital Publishing Industry Based on Game-Theory
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Expanded Study on the accumulation effect of tourism under the constraint of structure
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Unstructured P2P Network Load Balance Strategy Based on Multilevel Partitioning of Hypergraph
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on the method of information system risk state estimation based on clustering particle filter
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Demand forecasting and information platform in tourism
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Physical-chemical properties studying of molecular structures via topological index calculating
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Local kernel nonparametric discriminant analysis for adaptive extraction of complex structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- City traffic flow breakdown prediction based on fuzzy rough set
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Conservation laws for a strongly damped wave equation
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Blending type approximation by Stancu-Kantorovich operators based on Pólya-Eggenberger distribution
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Computing the Ediz eccentric connectivity index of discrete dynamic structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A discrete epidemic model for bovine Babesiosis disease and tick populations
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Study on maintaining formations during satellite formation flying based on SDRE and LQR
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Relationship between solitary pulmonary nodule lung cancer and CT image features based on gradual clustering
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- A novel fast target tracking method for UAV aerial image
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Fuzzy comprehensive evaluation model of interuniversity collaborative learning based on network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Conservation laws, classical symmetries and exact solutions of the generalized KdV-Burgers-Kuramoto equation
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- After notes on self-similarity exponent for fractal structures
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Excitation probability and effective temperature in the stationary regime of conductivity for Coulomb Glasses
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Comparisons of feature extraction algorithm based on unmanned aerial vehicle image
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Research on identification method of heavy vehicle rollover based on hidden Markov model
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Classifying BCI signals from novice users with extreme learning machine
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Topics on data transmission problem in software definition network
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Statistical inferences with jointly type-II censored samples from two Pareto distributions
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Estimation for coefficient of variation of an extension of the exponential distribution under type-II censoring scheme
- Special issue on Nonlinear Dynamics in General and Dynamical Systems in particular
- Analysis on trust influencing factors and trust model from multiple perspectives of online Auction
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Coupling of two-phase flow in fractured-vuggy reservoir with filling medium
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Production decline type curves analysis of a finite conductivity fractured well in coalbed methane reservoirs
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Flow Characteristic and Heat Transfer for Non-Newtonian Nanofluid in Rectangular Microchannels with Teardrop Dimples/Protrusions
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- The size prediction of potential inclusions embedded in the sub-surface of fused silica by damage morphology
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Research on carbonate reservoir interwell connectivity based on a modified diffusivity filter model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- The method of the spatial locating of macroscopic throats based-on the inversion of dynamic interwell connectivity
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Unsteady mixed convection flow through a permeable stretching flat surface with partial slip effects through MHD nanofluid using spectral relaxation method
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- A volumetric ablation model of EPDM considering complex physicochemical process in porous structure of char layer
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Numerical simulation on ferrofluid flow in fractured porous media based on discrete-fracture model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Macroscopic lattice Boltzmann model for heat and moisture transfer process with phase transformation in unsaturated porous media during freezing process
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Modelling of intermittent microwave convective drying: parameter sensitivity
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Simulating gas-water relative permeabilities for nanoscale porous media with interfacial effects
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Simulation of counter-current imbibition in water-wet fractured reservoirs based on discrete-fracture model
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Investigation effect of wettability and heterogeneity in water flooding and on microscopic residual oil distribution in tight sandstone cores with NMR technique
- Special Issue on Advances on Modelling of Flowing and Transport in Porous Media
- Analytical modeling of coupled flow and geomechanics for vertical fractured well in tight gas reservoirs
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Special Issue: Ever New "Loopholes" in Bell’s Argument and Experimental Tests
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- The ultimate loophole in Bell’s theorem: The inequality is identically satisfied by data sets composed of ±1′s assuming merely that they exist
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Erratum to: The ultimate loophole in Bell’s theorem: The inequality is identically satisfied by data sets composed of ±1′s assuming merely that they exist
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Rhetoric, logic, and experiment in the quantum nonlocality debate
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- What If Quantum Theory Violates All Mathematics?
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Relativity, anomalies and objectivity loophole in recent tests of local realism
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- The photon identification loophole in EPRB experiments: computer models with single-wing selection
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Bohr against Bell: complementarity versus nonlocality
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Is Einsteinian no-signalling violated in Bell tests?
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Bell’s “Theorem”: loopholes vs. conceptual flaws
- Special Issue on Ever-New "Loopholes" in Bell’s Argument and Experimental Tests
- Nonrecurrence and Bell-like inequalities
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Three-dimensional computer models of electrospinning systems
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Electric field computation and measurements in the electroporation of inhomogeneous samples
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Modelling of magnetostriction of transformer magnetic core for vibration analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Comparison of the fractional power motor with cores made of various magnetic materials
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Dynamics of the line-start reluctance motor with rotor made of SMC material
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Inhomogeneous dielectrics: conformal mapping and finite-element models
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Topology optimization of induction heating model using sequential linear programming based on move limit with adaptive relaxation
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of inter-turn short-circuit at start-up of induction machine based on torque analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Current superimposition variable flux reluctance motor with 8 salient poles
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Modelling axial vibration in windings of power transformers
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field analysis & eddy current losses calculation in five-phase tubular actuator
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Hybrid excited claw pole generator with skewed and non-skewed permanent magnets
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Electromagnetic phenomena analysis in brushless DC motor with speed control using PWM method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field-circuit analysis and measurements of a single-phase self-excited induction generator
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- A comparative analysis between classical and modified approach of description of the electrical machine windings by means of T0 method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Field-based optimal-design of an electric motor: a new sensitivity formulation
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Application of the parametric proper generalized decomposition to the frequency-dependent calculation of the impedance of an AC line with rectangular conductors
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Virtual reality as a new trend in mechanical and electrical engineering education
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Holonomicity analysis of electromechanical systems
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- An accurate reactive power control study in virtual flux droop control
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Localized probability of improvement for kriging based multi-objective optimization
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Research of influence of open-winding faults on properties of brushless permanent magnets motor
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Optimal design of the rotor geometry of line-start permanent magnet synchronous motor using the bat algorithm
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Model of depositing layer on cylindrical surface produced by induction-assisted laser cladding process
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of inter-turn faults in transformer winding using the capacitor discharge method
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- A novel hybrid genetic algorithm for optimal design of IPM machines for electric vehicle
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Lamination effects on a 3D model of the magnetic core of power transformers
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Detection of vertical disparity in three-dimensional visualizations
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Calculations of magnetic field in dynamo sheets taking into account their texture
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- 3-dimensional computer model of electrospinning multicapillary unit used for electrostatic field analysis
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Optimization of wearable microwave antenna with simplified electromagnetic model of the human body
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Induction heating process of ferromagnetic filled carbon nanotubes based on 3-D model
- Special Issue: The 18th International Symposium on Electromagnetic Fields in Mechatronics, Electrical and Electronic Engineering ISEF 2017
- Speed control of an induction motor by 6-switched 3-level inverter