Next Article in Journal
Deep Learning Empowered Structural Health Monitoring and Damage Diagnostics for Structures with Weldment via Decoding Ultrasonic Guided Wave
Previous Article in Journal
Multi-Sensor Data Fusion with a Reconfigurable Module and Its Application to Unmanned Storage Boxes
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Noise-Adaption Extended Kalman Filter Based on Deep Deterministic Policy Gradient for Maneuvering Targets

School of Aerospace Engineering, Beijing Institute of Technology, Beijing 100081, China
*
Author to whom correspondence should be addressed.
Sensors 2022, 22(14), 5389; https://doi.org/10.3390/s22145389
Submission received: 5 June 2022 / Revised: 9 July 2022 / Accepted: 18 July 2022 / Published: 19 July 2022
(This article belongs to the Section Physical Sensors)

Abstract

:
Although there have been numerous studies on maneuvering target tracking, few studies have focused on the distinction between unknown maneuvers and inaccurate measurements, leading to low accuracy, poor robustness, or even divergence. To this end, a noise-adaption extended Kalman filter is proposed to track maneuvering targets with multiple synchronous sensors. This filter avoids the simultaneous adjustment of the process model and measurement model without distinction. Instead, the maneuver detection based on the Dempster-Shafer evidence theory is constructed to achieve the reliable distinction between unknown maneuvers and inaccurate measurements by fusing multi-sensor information, which effectively improves the robustness of the filter. Moreover, the adaptive estimation of the process noise covariance is modeled by a Markovian decision process with a proper reward function. Deep deterministic policy gradient is designed to obtain the optimal process noise covariance by taking the innovation as the state and the compensation factor as the action. Furthermore, the recursive estimation of the measurement noise covariance is applied to modify a priori measurement noise covariance of the corresponding sensor. Finally, the fusion algorithm is developed for the global estimation. Simulation experiments are carried out in two scenarios, and simulation results illustrate the feasibility and superiority of the proposed algorithm.

1. Introduction

With the development of high maneuvering targets, such as hypersonic aircrafts and missiles, maneuvering target tracking has recently drawn a lot of attention [1,2]. During the past few decades, lots of tracking methods have been developed and investigated for maneuvering targets [3,4,5]. Among the existing target tracking approaches, designing an appropriate model for the target maneuvering motion is regarded as an important part of decreasing the tracking errors caused by the model mismatch. Therefore, many maneuver models were proposed, such as constant acceleration (CA) [6], Singer model [7], current statistical model (CS) [8]. In contrast to single model methods, the interactive multiple model (IMM) algorithm [9,10] has been widely applied because of its adaptive capability for maneuvering target tracking problems. By mapping the motion mode to a model set, IMM performs the parallel filter for each model. Furthermore, based on the residual information and a priori information, the state estimation results of each model are weighted and synthesized to accurately achieve the maneuvering target tracking. Considering the limited performance of IMM based on the single platform, Wang et al. [11] proposed a multi-platform maneuvering target tracking algorithm based on IMM and the best linear unbiased estimate filter. Moreover, an adaptive interacting multiple model algorithm based on information-weighted consensus was proposed [12], which presented better adaptability and accuracy than the classical IMM. To cope with the miss detections and false alarms in a low-observable environment, a state-dependent IMM based on the particle filter was presented [13]. However, the above IMM algorithms usually use a fixed set of models, so a large number of model sets is required when solving the problem of maneuvering target tracking. To alleviate this problem, the variable structure multiple model (VSMM) method has been proposed [14]. Furthermore, a VSMM version of the consensus filter was presented [15], where the expected mode augmentation was introduced to guarantee the model set adaption. In addition, the particle swarm optimization technique was utilized to improve VSMM [16]. However, for maneuvering target tracking in practice, multiple models cannot fully cover the modes of the target’s motion, which may degrade the tracking performance. Additionally, excessive numbers of models also generate large calculations in many practical applications.
On the other hand, the filtering algorithm is regarded as an important issue to cope with maneuvering target tracking problems. Practically, extended Kalman filter (EKF) [17] has been widely applied for many nonlinear systems during the past few years. EKF is developed based on the Kalman filter and introduces the first-order Taylor expansion to approximate the nonlinear function. However, the first-order Taylor expansion of EKF cannot, at times, satisfy the tracking accuracy. To this end, other nonlinear filter algorithms including unscented Kalman filter (UKF) [18,19] and cubature Kalman filter (CKF) [20] were proposed. By adopting the unscented transformation and spherical-radial principle, UKF and CKF can achieve second-order accuracy without calculating the Jacobian matrix. In order to further improve the robustness of the conventional filters, the strong tracking filter (STF) was proposed by Zhou et al. [21,22]. This algorithm introduces the orthogonal principle of residual sequences into the classical EKF to modify the prediction of the covariance matrix with a time-varying fading factor. When the state estimation of EKF deviates from the actual state, the effect of the old observations on the current filter estimation is reduced using the time-variant fading factor whereas the effect of the new observation is increased [23]. Accordingly, the robustness and accuracy of the classical EKF were improved. In order to improve the performance of STF, UKF and CKF were introduced to replace EKF [24,25]. An adaptive strong tracking particle filter algorithm was established by combing STF and the particle filter (PF), which demonstrated that the proposed method could provide better tracking precision than the classical methods [26]. Since the traditional strong tracking filter only considers the first-order Taylor expansion, a fast-strong tracking CKF was proposed [27], which expanded the number of fading factors from one to two. Sequentially, it extracted the third-order term information and achieved second-order accuracy. To implement higher tracking accuracy for the maneuvering target tracking, many improved strong tracking cubature Kalman filter (STCKF), such as strong tracking spherical simplex-radial CKF [28], fifth-degree STCKF [29], Bayesian-based strong tracking interpolatory CKF [30], model-based strong tracking square-root CKF [31], have recently been proposed. In addition, Ma et al. [32] added STF into the sub-filter of IMM to overcome the low tracking accuracy when dealing with maneuvering situations. However, in practical applications, it is found that the detection and tracking ability of the STF method will be reduced when the maneuver of the target is small. As is known, the residuals of range measurements are usually much bigger than the residuals of azimuth angle and elevation angle measurements, which leads STF to different sensitivities of different residual components. To this end, Jiang et al. [33] proposed a residual-normalized strong tracking filter (RNSTF) by designing the weight of the residual components. However, the process noise is not considered.
The aforementioned algorithms adopt the innovation, also known as the predictive residual, to realize maneuver detection and compensation, because the innovation will increase significantly when the model mismatch is caused by the unknown maneuver. However, the sensor signal may be disturbed or blocked due to the influence of a harsh environment, making the statistical characteristics of measurement noise uncertain and time varying. Inaccurate a priori measurement noise covariance can also lead to increased innovation. In that case, the aforementioned algorithms are too sensitive to inaccurate measurements, leading to filter divergence. To solve the problem of inaccurate a priori knowledge, several adaptive Kalman filters (AKF) with noise sensing capability were established [34,35]. Unfortunately, the existing methods only can achieve the second-order estimation accuracy [36,37], and the adaptive KF cannot distinguish between model mismatch and inaccurate a priori measurement noise. In addition, adaptive KFs use the innovation to adjust the process noise and measurement noise simultaneously, which leads to poor stability.
Inspired by the strong representation capability of neural networks [38,39], several filters based on reinforcement learning have been studied. Hu et al. [40] designed an attitude estimator by combining Lyapunov’s method and the deep reinforcement learning algorithm. Tang et al. [41] combined the classic EKF with the deep reinforcement learning algorithm to realize the attitude estimation of the navigation system, which introduced a gain matrix of the residual and took it as the action to learn. Gao et al. [42] proposed an adaptive Kalman filter based on the deep deterministic policy gradient (DDPG) algorithm for ground vehicles, which took the integrated navigation system as the environment to obtain the process noise covariance matrix estimation. However, this adaptive filter takes the change in noise vector as the action to learn, resulting in poor filter stability. Additionally, the process noise covariance matrix of Inertial Navigation System (INS) error model will not experience a great change because it represents the inherent performance of the inertial sensor [42], which is different from the target tracking problem.
Motivated by the above investigation, a noise-adaption EKF is proposed in this paper to address the problem of maneuvering target tracking. Based on multiple synchronous sensors, the maneuver detection is constructed by utilizing Dempster-Shafer (D-S) evidence theory [43] to achieve the fused detection of multiple sensors. A Markovian decision process with a proper reward function is modeled for the adaptive estimation of the process noise covariance, and DDPG is designed to learn the compensation factor and feed it into EKF so that the improved filter can adaptively cope with the unknown maneuver. If the detection declares the occurrence of inaccurate measurement noise, the recursive measurement noise estimation is applied to the corresponding sensor. Finally, the local estimations are fused to obtain the target’s global estimation. When the unknown maneuver and mismatched measurement noise emerge, the proposed filter can correct noise covariance adaptively. Distinct from the aforementioned algorithms, the proposed filter avoids the simultaneous adjustment of process model and measurement model without distinction, which effectively improves the robustness of the filter. Moreover, the application the deep deterministic policy gradient method in solving maneuver target tracking problems is explored in this paper.
The remainder of this paper is organized as follows: Section 2 introduces mathematical models and the formula of EKF. Section 3 provides the maneuver detection based on D-S evidence theory in detail, and the framework of the noise-adaption EKF is presented. In Section 4, the process noise adaption based on DDPG is designed. Moreover, the recursive measurement noise estimation and the fusion algorithm are completed. Finally, simulation results and conclusions are shown in Section 5 and Section 6, respectively.

2. Problem Formulation

The process model of the target is given by
x k + 1 = f x k + w k
where k denotes the index of discrete-time. x k represents the state vector, and f ( ) is the state transition function. The process noise w k is assumed to be zero-mean Gaussian white noise with the covariance matrix Q k .
The measurement model of sensors can be represented as
z k + 1 = h x k + 1 + v k + 1
where z k + 1 is the measurement vector, and h ( ) is the measurement mapping function. v k + 1 is the measurement noise, whose covariance matrix is R k + 1 .
Since EKF has the advantages of simple algorithm and fast convergence, it has been widely applied in nonlinear systems [17]. Specifically, EKF can be divided into two stages. The first stage is the one-step prediction based on the process model
x ^ k + 1 | k = f x ^ k
P k + 1 | k = F k + 1 | k P k | k F k + 1 | k T + Q k
where x ^ k | k is the state estimation and P k | k is the covariance matrix, x ^ k + 1 | k and P k + 1 | k are the corresponding predictions. The state transition matrix F k + 1 | k is defined as the first-order Taylor expansion of the state transition function.
F k + 1 | k = f x x x = x ^ k
The second stage is the one-step update based on the measurement. The state vector and its covariance matrix are updated as
K k + 1 = P k + 1 | k H k + 1 T H k + 1 P k + 1 | k H k + 1 T + R k + 1 1
x ^ k + 1 = x ^ k + 1 | k + K k + 1 z k + 1 h x ^ k + 1 | k
P k + 1 | k + 1 = I K k + 1 H k + 1 P k + 1 | k
where K k + 1 is the gain matrix, and H k + 1 is defined as
H k + 1 = h x x x = x ^ k + 1 | k
As the main prior information of the system, the process noise Q and the measurement noise R are of great significance to the estimation performance and stability of the filter. Q and R represent the confidence degree in models and measurements, respectively. If Q and R are smaller than the true noise distribution, the uncertainty range of the true state is too narrow, resulting in estimation bias. Conversely, if Q and R are larger than the true noise distribution, it may lead to filter divergence. Additionally, inaccurate Q and R can impair the estimation accuracy.

3. Maneuver Detection and the Framework

3.1. Maneuver Detection Based on D-S Evidence Theory

The key to maneuver detection is to design an appropriate detection strategy to detect the target’s maneuver precisely and timely. As stated in the introduction, the detection depending on the innovation from single-source information is not reliable. To improve the accuracy of the maneuver detection, the maneuver detection with a sliding-window structure based on D-S evidence theory is proposed in this section by introducing multiple synchronous sensors’ information.
D-S evidence theory is a fusion rule established on a nonempty finite space, which includes a limited number of subsets [43]. Through independent observations by sensors, it can fuse observation results and give a joint judgment to improve the confidence and accuracy of events. D-S evidence theory can combine the evidence more intuitively and easily, and it has the expression ability of unknown and uncertain situations by calculating the probability of the set of multiple events.
Consider all the subsets of the finite space Θ as 2 Θ , including Θ and an empty set Φ , and define the map m : 2 Θ [ 0 , 1 ] , for A Θ , it satisfies
A Θ m A = 1
m Φ = 0
where the map m is called the basic probability assignment function. m A is called the mass function of A , which indicates the degree of confidence for A according to the current observation.
For the problem of maneuvering target tracking, the target has two movement modes: maneuver or not, so there are two events in the maneuver detection problem: “Maneuver” and “Normal”, denoted as A 1 , A 2 , respectively. However, when the degree of confidence tends to zero, unreasonable fusion results will be obtained, which is always called as Zadeh paradox [43]. To avoid the Zadeh paradox, one more event “uncertainty” is added, denoted as A 3 = A 1 , A 2 , and its confidence degree is set to 0.01.
Suppose there are N sensors applied in the target’s measurement mission, denoted as S i i = 1 , 2 , , N , and the measurement of S i at time k is z i , k . The innovation is defined as the difference between actual measurement value and predictive measurement value.
γ i , k + 1 = z i , k + 1 z ^ i , k + 1 | k
where z ^ i , k + 1 | k = h i x ^ i , k + 1 | k is the predictive measurement. The innovation satisfies
E γ i , k + 1 = 0
E γ i , k + 1 γ i , k + 1 T = H i , k + 1 P i , k + 1 | k H i , k + 1 T + R i , k + 1
Following this, the detection variable is constructed based on the innovation.
η i , k + 1 = γ i , k + 1 T H i , k + 1 P i , k + 1 | k H i , k + 1 T + R i , k + 1 1 γ i , k + 1
Since the innovation is subject to Gaussian distribution, the detection variable is supposed to be subject to χ 2 distribution with n degree of freedom, where n is the dimension of the innovation vector. Therefore, the maneuver probability is defined as
P i , k + 1 ( Maneuver ) = 0 η i , k + 1 χ n 2 x d x
It can be seen from Equation (16) that, the innovation is considered to be entirely caused by the unknown maneuver, hypothetically. The increase in the innovation indicates bigger maneuver probability.
Based on the definition of the maneuver probability, the mass function of S i is given as
m i , k + 1 A 1 = P i , k + 1 Maneuver
m i , k + 1 A 2 = 1 P i , k + 1 Maneuver 0.01
m i , k + 1 A 3 = 0.01
As mentioned above, the mismatch between the real measurement noise and a priori measurement noise can also lead to the innovation’s increase. As a result, the maneuver probability determined by the innovation is unreliable. A joint detection mechanism is developed by fusing maneuver detection results of multiple synchronous sensors to improve the accuracy and reliability of the maneuver detection. For N independent pieces of evidence with N e events, the fused mass function of A 1 can be merged by D-S evidence theory as follows
m k + 1 A 1 = A 1 A N e = A 1 m 1 , k + 1 A 1 · m 2 , k + 1 A 2 m N , k + 1 A N e 1 A 1 A N e = Φ m 1 , k + 1 A 1 · m 2 , k + 1 A 2 m N , k + 1 A N e = A 1 A N e = A 1 m 1 , k + 1 A 1 · m 2 , k + 1 A 2 m N , k + 1 A N e A 1 A N e Φ m 1 , k + 1 A 1 · m 2 , k + 1 A 2 m N , k + 1 A N e
where N e = 3 in this paper.
Similarly, the fused mass function of A 2 and A 3 can be acquired, denoted as m k + 1 A 2 and m k + 1 A 3 , respectively. If m k + 1 A 1 m k + 1 A 2 , it means that the target is detected to be maneuvering according to the fusion of multiple sensors at time k . Conversely, the target is not maneuvering when m k + 1 A 1 < m k + 1 A 2 , and the mismatch of the a priori measurement noise is the main reason for the increased innovation.
However, the maneuver detection based on the current time is unstable. Furthermore, the sliding window structure is introduced into the maneuver detection to improve the stability of detection, where the detection depends not only on the current state but also on the neighboring states.
The size of the sliding window is set as N s w , and the final mass function m k + 1 f can be calculated by
m k + 1 f A 1 = A 1 A N e = A 1 m k + 2 N s w A 1 m k A N e · m k + 1 A N e A 1 A N e Φ m k + 2 N s w A 1 m k A N e · m k + 1 A N e k + 1 N s w A 1 A N e = A 1 m 1 A 1 m k A N e · m k + 1 A N e A 1 A N e Φ m 1 A 1 m k A N e · m k + 1 A N e k + 1 < N s w
Similarly, the final mass function m k + 1 f ( A 2 ) and m k + 1 f ( A 3 ) can be obtained. According to the fused detection result, there are three conditions of the tracking problem. (a) When m k + 1 f ( A 1 ) m k + 1 f ( A 2 ) , the target is detected to be maneuvering, and the adaptive process noise estimation needs to be introduced to deal with unknown maneuvers. (b) If m k + 1 f ( A 1 ) < m k + 1 f ( A 2 ) and m i , k + 1 ( A 1 ) m i , k + 1 ( A 2 ) , the target is not maneuvering, and the mismatch of measurement noise emerges, so the measurement noise adaption of S i is necessary. (c) There are no above two conditions when m k + 1 f ( A 1 ) < m k + 1 f ( A 2 ) and m i , k + 1 ( A 1 ) < m i , k + 1 ( A 2 ) , so EKF can cope with the target tracking task.

3.2. The Framework of the Noise-Adaption EKF

Based on the above maneuver detection, a noise-adaption EKF is proposed to adaptively cope with the unknown maneuver and inaccurate measurement noise. The framework of the proposed filter is shown in Figure 1.
To achieve the accurate compensation for unknown maneuvers and the inaccurate measurement noise covariance, multi-sensor information undergoes the maneuver detection. Whether or not the process noise adaption or the measurement noise adaption proceeds is determined by the maneuver detection. If the target is detected to be maneuvering, the adaptive process noise is calculated by DDPG and introduced into the filter to cope with the model mismatch caused by the unknown maneuver. If the inaccurate measurement noise covariance is detected to be the main reason for the innovation’s increase, the recursive measurement noise estimation is applied to the corresponding sensor. Sequentially, the local estimations are fused to obtain the global estimation of the target. When the unknown maneuver or mismatched measurement noise emerge, the proposed filter can estimate the maneuvering target’s state with high performance.

4. Noise-Adaption EKF for Maneuvering Targets

4.1. Process Noise Adaption Based on DDPG

For the problem of maneuvering target tracking, the main task is to find a tracking strategy to estimate the target’s station rapidly and accurately. However, the accurate mathematical models of non-cooperative targets cannot be obtained. When the target is maneuvering, the estimation error increases due to the model mismatch. To cope with the unknown maneuver, an effective method is to adaptively estimate the process noise covariance online. To this end, a process noise adaption method based on DDPG is proposed in this section. Through its self-learning and optimization capabilities, DDPG algorithm can adaptively cope with the unknown maneuver.
DDPG is known as one of the reinforcement learning algorithms for the continuous action strategy. The interactive learning process of DDPG is formalized as the Markov decision process (MDP), which can be defined by four elements: the state S = s 1 , s 2 , , the action A = a 1 , a 2 , , the reward R = r 1 , r 2 , , and the state transition probability P s k + 1 | s k , a k . The framework of DDPG is shown in Figure 2. The agent generates an action to interact with the environment at first, and then under the joint effects of action and environment, a new state is generated, and the environment gives a reward to the critic. Afterwards, the critic calculates the action-value function to evaluate the given policy, then the action policy is further optimized according to the evaluation results.
The adaptive estimation of the process noise covariance is defined as
Q ^ k = λ k Q ^ k 1
where Q ^ k is the adaptive process noise covariance, and its initial value is the a priori process noise covariance matrix. λ k > 1 is the compensation factor. This adaptive estimation form is more robust due to fewer parameters.
Correspondingly, the prediction of the covariance matrix in Equation (4) is updated as
P k + 1 | k = F k + 1 | k P k | k F k + 1 | k T + Q ^ k
Following by this, the problem of designing the maneuvering tracking strategy is transformed into the determination of the compensation factor, which can be described as an MDP. DPPG algorithm is designed to learn the compensation factor, so the action is defined as
a k = λ k
The innovation reflects the degree of model mismatch. The larger the innovation, the larger the model error, and the compensation factor needs to be increased accordingly. Therefore, the agent state is defined as the filter’s innovation in Equation (12), which contains three-dimensional innovation: range, azimuth angle and elevation angle, i.e.,
s k = γ k T = γ k , r , γ k , β , γ k , ε T
When the environment, i.e., the filter, receives an action, a sufficient reward mechanism is required to evaluate the filter performance under the current action. Therefore, the filter residual is taken as the evaluation index, which is expressed as
φ k = z k z ^ k = z k h x ^ k
In practice, the residuals of range measurements are usually much bigger than the residuals of azimuth angle and elevation angle measurements in practice, which leads to different sensitivity to different residual components. To make the filter equally sensitive to residual elements, a weighting matrix W is introduced for normalizing the residuals.
W = 1 / σ r 0 0 0 1 / σ β 0 0 0 1 / σ ε
where σ r , σ β , and σ ε represents the measurement errors’ standard deviation of range, azimuth angle, and elevation angle, respectively.
Therefore, the reward function is established as follows
r k = t r [ ( W φ k ) ( W φ k ) T ]
where t r [ ] is the trace operation.
In DDPG algorithm, two neural networks including the actor network and the critic network, are utilized to approximate the action function and the action-value function. Denote A μ ( s k ) as the action function, which is parameterized by μ . It maps from state to action, i.e., a k = A μ ( s k ) . Moreover, the action-value function is denoted as Q ω ( s k , a k ) , which is parameterized by ω . Additionally, to enhance the convergence of training, one target actor network and one target critic network are introduced into DDPG, denoted as A μ ( s k ) and Q ω ( s k , a k ) , respectively.
The optimal action policy is realized by maximizing the expected total reward
μ = arg max μ J ( A μ )
The expected total reward is defined as
J ( A μ ) = E Q ω ( s , a ) | s = s k , a = A μ ( s k )
Therefore, the actor function is optimized toward the gradient of the expected total reward
μ J ( A μ ) = μ A μ ( s k ) a k Q ω ( s k , a k )
Similarly, the action-value function is optimized by minimizing the loss function
ω = arg min ω L ( ω )
The temporal difference error δ k is utilized to establish the loss function
L ( ω ) = δ k 2 = [ r k + ξ Q ω ( s k + 1 , A μ ( s k + 1 ) ) Q ω ( s k , A μ ( s k ) ) ] 2
where r k is the reward, and ξ is the discounting factor.
The actor-value function is optimized toward the gradient of the loss function
ω L ( ω ) = 2 δ k ω Q ω ( s k , a k )
To improve the stability in the DDPG training process, there is a replay memory buffer to store the training samples. At every training step, training samples with a size N s a m p l e are utilized to train the actor and critic networks. The current transition experience ( s k , a k , r k , s k + 1 ) will be added into the buffer to replace the oldest one.
The actor network is updated by the Adam optimizer
μ k + 1 = f A d a m ( μ k , μ J ( A μ ) )
μ J ( A μ ) = 1 N s a m p l e i = 1 N s a m p l e μ A μ ( s i ) a k Q ω ( s i , a i )
Similarly, the critic network is updated using the negative gradient of the loss function
ω k + 1 = f A d a m ( ω k , ω L ( ω ) )
ω L ( ω ) = 1 N s a m p l e t = 1 N s a m p l e δ i ω Q ω ( s i , a i )
At the end of each sample training, the two target networks are soft updated as
μ k + 1 = τ μ k + 1 + ( 1 τ ) μ k
ω k + 1 = τ ω k + 1 + ( 1 τ ) ω k
where τ is the updating rate.
The implementation framework of the adaptive estimation of process noise based on DDPG is shown in Figure 3.
The process noise adaption based on DDPG is summarized in Algorithm 1.
Algorithm 1 The process noise adaption based on DDPG
1 Initialize the parameters of the actor network and critic network
2 Initialize target networks by copying the actor and critic network
3 Initialize the replay memory buffer
For each episode, perform the following steps
4 Initialize the estimation state and its covariance matrix
  For each timestep, perform the following steps
5   Generate an action based on the actor network and the current state a k = A μ ( s k ) + 𝒩 k , where the random noise is generated by Ornstein-Uhlenbeck process
6   Execute the action, i.e., the compensation factor in the filter to obtain a new state s k + 1 and a new reward r k
7   Store the sample ( s k , a k , s k + 1 , r k ) in the buffer
8   Randomly select N S a m p l e samples from the buffer
9   Calculate the temporal difference error δ p of each sample
    δ p = r p + ξ Q ω ( s p + 1 , A μ ( s p + 1 ) ) Q ω ( s p , A μ ( s p ) )
10   Calculate the policy gradient
    μ J ( A μ ) = 1 N S a m p l e p = 1 N S a m p l e μ A μ ( s p ) a t Q ω ( s p , a p )
11   Update the actor network by Adam optimizer:
    μ k + 1 = f A d a m ( μ J ( A μ ) )
12   Update the critic network
    ω ( ω ) = 1 N S a m p l e p = 1 N S a m p l e 2 δ p ω Q ω ( s p , a p )
    ω k + 1 = f A d a m ( ω t , ω ( ω ) )
13   Update the two target networks by soft update
    μ k + 1 = τ μ k + 1 + ( 1 τ ) μ k
    ω k + 1 = τ ω k + 1 + ( 1 τ ) ω k
End timestep
End episode

4.2. Recursive Measurement Noise Estimation

When the sensor’s maneuver detection result is inconsistent with the fused maneuver detection result, the corresponding sensor’s measurement model is considered not to match a priori knowledge. In this case, the adaptive estimation method based on DDPG is no longer applicable to deal with it. Since the target is non-cooperative, the deviation between the process model and the actual model exists, so it is difficult to realize the optimal estimation of measurement noise in a similar way to the adaptive estimation of process noise. To modify the measurement noise adaptively, the recursive estimation of measurement noise is introduced [34].
The estimation of R ^ k + 1 can be obtained by maximizing the a posteriori density function, which is given by
R ^ k + 1 = 1 k + 1 j = 1 k + 1 z j h ( x ^ j ) z j h ( x ^ j ) T
The residual can be represented as
z j h ( x ^ j ) = z j h ( x ^ j | j 1 + K j γ j ) = z j h ( x ^ j | j 1 ) H j K j γ j + ο ( K j γ j ) I H j K j γ j
Substitute Equation (42) into Equation (41), yields
R ^ k + 1 = 1 k + 1 j = 1 k + 1 I H j K j γ j γ j T I H j K j T
The expectation of the measurement noise can be expressed as (the detailed derivation can be found in the appendix of [34].)
E R ^ k + 1 = E 1 k + 1 j = 1 k + 1 I H j K j γ j γ j T I H j K j T = 1 k + 1 j = 1 k + 1 R j I H j K j H j P j | j 1 H j T = R 1 k + 1 j = 1 k + 1 I H j K j H j P j | j 1 H j T
The statistical residual covariance is calculated as the variance of historical residual sequence
R ¯ k + 1 = I H k + 1 K k + 1 γ k + 1 γ k + 1 T I H k + 1 K k + 1 T + H k + 1 P k + 1 | k H k + 1 T
Accordingly, to approximate the real measurement covariance, the modified measurement covariance is updated as the following recursive form
R ^ k + 1 = ( 1 ρ k + 1 ) R ^ k + ρ k + 1 R ¯ k + 1
ρ k + 1 = 1 b 1 b k + 1
where ρ k + 1 is the weighting factor, and b is a fading factor. The initial value of R ^ k is the a priori measurement noise covariance matrix.
Therefore, the gain matrix in Equation (6) is replaced as
K k + 1 = P k + 1 | k H k + 1 T ( H k + 1 P k + 1 | k H k + 1 T + R ^ k + 1 ) 1
By modifying the measurement covariance, the gain matrix is adjusted, then the impact of inaccurate a priori measurement noise is reduced.

4.3. Fusion Algorithm

The local estimations from multiple sensors are fused in this section. Since the cross-covariance matrixes of different sensors are unknown, the fault-tolerant generalized convex combination algorithm (FGCC) [44] based on information theory is introduced in this section.
For two local estimations x ^ 1 and x ^ 2 , the fusion rule of FGCC is
x ^ f = P f υ 1 P 1 1 x ^ 1 + υ i P 2 1 x ^ 2
P f = ( υ 1 P 1 1 + υ 2 P 2 1 ) 1
υ 1 + υ 2 = δ
where P 1 and P 2 are corresponding covariance matrices, υ 1 and υ 2 are the weighting parameters, and the δ is an adaptive parameter constructed as
δ = H ( P 1 ) + H ( P 2 ) H ( P 1 ) + H ( P 2 ) + I ( P 1 , P 2 )
In the above equation, is the Shannon entropy, and is the symmetrized Kullback-Leibler distance between two distributions known as J-divergence.
H ( P i ) = 1 2 log [ ( 2 π ) n | P i | ] + n 2
I ( P i , P j ) = 𝒟 ( P i , P j ) + 𝒟 ( P j , P i )
where n is the number of state vector dimensions, and 𝒟 is the Kullback-Leibler divergence.
D ( P i , P j ) = 1 2 [ ln | P j | | P i | + | | d x i j | | P j 1 + t r ( P i P j 1 ) n ]
where d x i j = x ^ i x ^ j ,and i , j 1 , 2 , i j .
The weights can be determined by the following equation
υ i = δ 𝒟 ( P i , P j ) 𝒟 ( P i , P j ) + 𝒟 ( P j , P i )
Obviously, the above algorithm can only be applied to the fusion of two local estimations. In order to improve the applicability of the fusion algorithm, an extended fault-tolerant generalized convex combination algorithm (EFGCC) is developed, which provides the general fusion rule for N > 2 .
Suppose there are N local estimations x ^ i ( i = 1 , , N ) and corresponding covariance matrices P i . The fusion form of EFGCC is given as
x ^ f = P f i = 1 N υ i P i 1 x ^ i
P f = ( i = 1 N υ i P i 1 ) 1
i = 1 N υ i = δ
where the adaptive parameter δ is updated as
δ = i = 1 N ( P i ) i = 1 N ( P i ) + i = 1 N j = i + 1 N ( P i , P j )
The definitions of the Shannon entropy and the symmetrized Kullback-Leibler distance are the same as above. The weighting parameter υ i can be determined by the following equation
υ i = δ f i ( 𝒟 ) j = 1 N f j ( 𝒟 )
where
f i ( 𝒟 ) = 𝒟 ( P i , P N ) j = 1 i 1 𝒟 ( P N , P j ) j = i + 1 N 1 𝒟 ( P N , P j ) i < N j = 1 N 1 𝒟 ( P N , P j ) i N
By the fusion rule of Equation (57), the global estimation for maneuvering targets is realized.

5. Simulation

In this section, the effectiveness and superiority of the proposed tracking method are demonstrated through numerical simulations.

5.1. Target Model

In the simulation experiments, the Singer model [7] is adopted as the process model in this paper, which describes the target acceleration as the colored noise rather than the white noise. The acceleration is assumed to be a first-order time correlation. The model can be given by
x k + 1 = F k + 1 | k x k + w k
The state vector x k = [ x k , v x , k , a x , k , y k , v y , k , a y , k , z k , v z , k , a z , k ] T , which includes the position, velocity, and acceleration in three directions.
The state transition matrix is defined as
F k + 1 | k = diag ( F x , F y , F z )
where
F x = F y = F z = 1 T ( e α T + α T 1 ) / α 2 0 1 ( 1 e α T ) / α 0 0 e α T
α is the target’s maneuvering frequency, and T is the sampling period.
The covariance matrix is calculated as
Q k = diag ( Q x , Q y , Q z )
where
Q x = Q y = Q z = 2 α σ a 2 q i j 3 × 3
q 11 = 1 2 α 5 1 e 2 α T + 2 α T + 2 α 3 T 3 / 3 2 α 2 T 2 4 α T e α T q 12 = q 21 = 1 2 α 4 e 2 α T + 1 2 e α T + 2 α T e α T 2 α T + α 2 T 2 q 13 = q 31 = 1 2 α 3 1 e 2 α T 2 α T e α T q 22 = 1 2 α 3 4 e α T 3 e 2 α T + 2 α T q 23 = q 32 = 1 2 α 2 e 2 α T + 1 2 e α T q 33 = 1 2 α 1 e 2 α T
The measurement vector is defined as z k = [ r k , β k , ε k ] T , where r k is the range, β k is the azimuth angle, and ε k is the elevation angle. The measurement mapping function is
h ( x k + 1 ) = x k + 1 2 + y k + 1 2 + z k + 1 2 arctan ( z k + 1 / x k + 1 ) arctan ( y k + 1 / x k + 1 2 + z k + 1 2 )
The initial covariance matrix of the measurement noise is
R = σ r 2 0 0 0 σ β 2 0 0 0 σ ε 2

5.2. Construction of Neural Networks

In the proposed process noise estimation based on DDPG, the actor network is used to learn the action policy from the input of the innovation [ γ k , r , γ k , β , γ k , ε ] T to the output of the compensation factor λ k , and the critic network is used to obtain the action-value function based on the innovation and the compensation factor. Inspired by [45,46], four-layer fully connected networks are commonly utilized in deep reinforcement learning applications. Hence the structure of the actor network is designed as shown in Figure 4, and the critic network is represented by the same network structure. Too few neurons will lead to underfitting. Conversely, too many neurons can lead to overfitting and increased training time. By referring to [42,45,46] and simulation experiments, the size of neural networks are set as in Table 1.
The activation function is tan h function, which is given by
tan h ( x ) = e x e x e x + e x
Simulation parameters are summarized in Table 2.
The simulation environment is defined as 6000 km × 100 km × 6000 km , in which the target tracking task is carried out. The training task includes 500 random episodes, and each episode runs 1000 timesteps. The maximum acceleration of the target is 30 m/s2, and the minimum acceleration is −30 m/s2. For each episode, the target randomly maneuvers with values uniformly distributed between the minimum and the maximum accelerations. According to the definition of the training environment and the maneuver space, training scenarios are constructed.

5.3. Simulation Results

To demonstrate the superiority of the proposed filter, IMM [9], STF [22], RNSTF [33], and AKF [34] are simulated for comparison. Two simulation scenarios are conducted in this section to illustrate the feasibility of the proposed noise-adaption EKF. In the first scenario, the target makes continuous time-varying maneuvers. In the second scenario, the target is set to make abrupt maneuvers to verify the performance against strong maneuvers.
In the simulation, the fading factor in the recursive measurement noise estimation and AKF b = 0.9 , and the maneuvering frequency in the Singer model α = 1 / 20 . The forgetting factor in STF and RNSTF is 0.95. CA model, Singer model, and CS model are adopted in IMM, and the maneuvering frequency in the CS model α = 1 / 20 . The initial probability of each sub model is 0.4 0.4 0.2 , and the Markov transition probability matrix is set as
P = 0.95 0.025 0.025 0.025 0.95 0.025 0.025 0.025 0.95
The root mean square error (RMSE) is generally used to estimate the tracking accuracy, given as
RMSE = j = 1 N M C x ^ k j x k j 2 / N M C
where x ^ k is the estimation value, and x k is the real value. N M C is the number of Monte Carlo experiments, which is 100 in the following simulations.

5.3.1. Continuous Time Varying Maneuver

In this scenario, the target’s acceleration is continuous time-varying in sinusoidal form, which can be described as
a = A sin ( ω t + φ 0 )
where A is the amplitude, ω is the frequency, and φ 0 is the initial phase. The entire flight process lasts 1000 s. The initial position is [800 km, 80 km, 800 km], and the initial velocity is [−300 m/s, 10 m/s, −300 m/s]. The sinusoidal parameters are set as shown in Table 3.
Assuming that there are three sensors at the origin to track the maneuvering target with a sampling period of 1 s, and a priori measurement errors are set as shown in Table 4. Furthermore, to verify the performance of the proposed noise-adaption EKF under the condition of inaccurate measurement noise, the magnitude of the range measurement noise of S 1 enlarged five times during 500–600 s, which is unknown to the filter.
The algorithms mentioned above are utilized for tracking solution, and the same fusion method, i.e., EFGCC, is adopted to obtain fusion trajectories. For convenience, the proposed noise-adaption EKF is denoted as NAEKF in the following simulation results. The estimated trajectories are shown in Figure 5.
The position estimation errors are presented in Figure 6. In order to correspond to the measurements, the position estimation errors are given in terms of range, azimuth angle and elevation angle. The position errors of NAEKF are smaller than that of other filters, especially in the stage of inaccurate measurement noise. Correspondingly, Figure 7 shows the σ -boundaries of position estimation errors. At the beginning of the simulation, position errors are generally large due to initialization errors, but the estimation accuracy gradually improves over time. After 100 s, the range error of the proposed filter converges to 3.27 m. The azimuth angle error reaches 0.0033°, and the elevation angle error is stable around 0.0029°. Due to the effect of inaccurate measurement noise between 500–600 s, the stable value of range errors reaches 3.54 m. Similarly, the azimuth angle error increases slightly and finally stabilizes at 0.0043°, and the elevation angle error stabilizes at 0.0043°. To compare local estimation accuracy of different algorithms, the detailed estimation errors are shown in Table 5, Table 6 and Table 7. Taking the range estimation of S 1 as an example, the estimation accuracy of NAEKF is 8.95%, 21.28% and 20.90% higher than that of IMM, STF and RNSTF, respectively, and the estimation error of AKF is almost seven times that of NAEKF. Obviously, the proposed filter has better tracking accuracy than other filters.
Figure 8 and Figure 9 show the velocity estimation errors and the corresponding σ -Boundary in three directions, respectively. As shown in simulation results, the velocity estimation accuracy of IMM, STF, RNSTF and AKF are worse than that of NAEKF. It can be seen from Figure 9 that the velocity estimation errors of STF and RNSTF increase significantly when inaccurate measurement noise occurs, while the result of IMM and NAEKF do not. Taking the velocity estimation in x direction as an example, the estimation error of STF increases from 24.85 m/s to 35.20 m/s, and that of RNSTF increases from 24.87 m/s to 35.27 m/s. The estimation error of IMM is stable around 18.20 m/s, while the estimation error of AKF reaches 98.65 m/s. In contrast, the velocity estimation error in x direction of NAEKF reaches 13.83 m/s. The tracking results in y and z directions are similar as that in x direction, which will not be repeated here. In the end, the velocity estimation accuracy of NAEKF reaches 14.21 m/s, which is the average of three directions.
The acceleration estimation errors and the corresponding σ -boundaries of acceleration estimation errors are presented in Figure 10 and Figure 11, separately. The average acceleration estimation accuracy of NAEKF is 1.27 m / s 2 , whereas that of IMM, STF, RNSTF and AKF is around 1.86 m / s 2 , 4.20 m / s 2 , 4.11 m / s 2 and 28.01 m / s 2 , respectively. It can be confirmed that the proposed NAEKF can effectively deal with unknown sinusoidal maneuvers and achieves better tracking performance than IMM, STF, RNSTF as well as AKF. Table 8 provides computing times of five algorithms. Since NAEKF adds steps such as maneuver detection, the computing time is slightly longer than that of STF and RNSTF. However, NAEKF takes less computing time than IMM and AKF, because the parallel calculation of sub filters in IMM and the simultaneous noise estimation in AKF are time-consuming.
On the basis of the above experiment settings, the magnitude of the angle measurement noises of S 1 also enlarged five times during 500–600 s. Simulation results show that the matrix singularity problem of AKF occurs in this simulation experiment. As described in the introduction, AKF shows poor stability, because it updates the process noise and measurement noise simultaneously without distinction. Therefore, IMM, STF, RNSTF and NAEKF are presented in this experiment.
Figure 12 and Figure 13 show the position estimation errors and the corresponding σ -Boundary. Although the inaccurate measurement noises lead to certain increases in estimation errors, NAEKF shows better estimation accuracy and robustness compared to other three algorithms. Taking the azimuth angle as an example, the estimation error of NAEKF is 0.0068°, while that of IMM reaches 0.0098°. Additionally, the estimation error of STF and RNSTF is 0.0159° and 0.0158°, respectively, which is more than twice the estimation error of NAEKF.
The estimation results of the velocity and acceleration are shown in Figure 14, Figure 15, Figure 16 and Figure 17. It is obvious that the proposed NAEKF can effectively deal with inaccurate measurement noises in this experiment and achieves the best estimation accuracy compared to other algorithms. The velocity estimation errors of IMM, STF and RNSTF are several times that of NAEKF, and the same conclusion can be drawn from the acceleration estimation results.

5.3.2. Abrupt Maneuver

In this scenario, the target’s acceleration is set to be abrupt, and the maneuver parameters are shown in Table 9. The initial position is [6000 km, 15 km, 6000 km], and the initial velocity is [−1000 m/s, 0 m/s, −1000 m/s].
The measurement errors are the same as in Table 4, and the magnitude of the range measurement noise of S 1 enlarged five times during 700–800 s. It should be noted that the matrix singularity problem of AKF occurs in this simulation scenario. Therefore, IMM, STF, RNSTF and NAEKF are presented in this section. The tracking results are shown in Figure 18.
The position estimation errors and the corresponding σ -boundaries are shown in Figure 19 and Figure 20, respectively. Simulation results show that the proposed filter can track the abrupt maneuver target effectively. Owing to the D-S maneuver detection, the proposed noise-adaption EKF can detect unknown maneuvers and inaccurate measurement noise simultaneously. As a result, the proposed filter can utilize the process noise adaption based on DDPG to adaptively cope with the unknown maneuver. It can be seen from Figure 19a that abrupt maneuvers cause several error increases in the tracking process, but they are quickly eliminated. When inaccurate measurement noise is detected, the proposed filter utilizes the recursive measurement noise adaption to weaken its influence. Certain increases in estimation errors are caused by inaccurate measurement noise during 700–800 s. The estimation errors of STF and RNSTF increase remarkably, especially when the inaccurate measurement noise appears. The estimation errors of different algorithms are shown in Table 10, Table 11 and Table 12. It is evident that the proposed filter achieves higher estimation accuracy than IMM, STF and RNSTF in both local estimation and fusion estimation.
Figure 21 and Figure 22 present velocity estimation errors and corresponding σ -boundaries. Velocity estimation errors in x and z directions of NAEKF are 77.32 m/s and 77.86 m/s, respectively. However, the estimation error in y direction reaches 146.70 m/s, because the maneuver in y direction is much bigger than other directions. Estimation errors of STF and RNSTF are significantly bigger than that of NAEKF. In contrast, IMM achieves better estimation accuracy than STF and RNSTF, but still worse than NAEKF.
According to acceleration estimation results in Figure 23, there are several peaks of acceleration tracking errors during abrupt maneuvers, but they decrease rapidly. The σ -boundaries of acceleration estimation errors are shown in Figure 24. The acceleration estimation accuracy in x direction of NAEKF is 4.97 m / s 2 , whereas that of IMM, STF and RNSTF is finally stabilized at 10.23 m / s 2 , 12.31 m / s 2 and 12.49 m / s 2 , respectively. Similarly, the acceleration estimation accuracy in z direction of NAEKF is 5.06 m / s 2 , and the estimation accuracy of IMM, STF and RNSTF is around 10.38 m / s 2 , 12.02 m / s 2 and 12.24 m / s 2 , respectively. Due to the greater maneuver, the acceleration estimation accuracy in y direction is worse than that in other directions. Specifically, the acceleration estimation error of NAEKF reaches 10.27 m / s 2 . In contrast, the acceleration estimation error of IMM, STF and RNSTF is around 14.66 m / s 2 , 18.93 m / s 2 , and 18.32 m / s 2 , respectively. Table 13 provides computing times of four algorithms. Similarly to the first scenario, the computing time of NAEKF is shorter than that of IMM, but slightly longer than that of STF and RNSTF.

6. Conclusions

To address the problem of maneuvering target tracking with inaccurate measurements, the noise-adaption EKF based on DDPG is proposed in this paper. The proposed filter avoids the simultaneous adjustment of the process model and the measurement model without distinction, which effectively improves the robustness of the filter. Within the framework of the noise-adaption EKF, the maneuver detection based on D-S evidence theory is constructed to distinguish between the unknown maneuver and inaccurate measurement noise simultaneously by fusing multi-sensor information. Moreover, a Markovian decision process of maneuver tracking is established to cope with unknown maneuvers. DDPG is developed to learn the adaptive estimation of the compensation factor and feed it to EKF. In addition, the recursive measurement noise estimation is applied to estimate a priori measurement noise covariance online. The local estimations are fused at last, achieving the global estimation of multiple sensors. The simulation results indicate that the proposed noise-adaption EKF is effective in both scenarios of continuous time-varying maneuver and the abrupt maneuver. As shown in simulation results, the proposed tracking method has a better tracking performance compared to IMM, STF, RNSTF and AKF.

Author Contributions

Conceptualization, S.T.; methodology, J.L. and J.G.; software, J.L.; validation, J.L. and J.G.; formal analysis, S.T.; investigation, J.G.; resources, S.T.; data curation, J.L.; writing—original draft preparation, J.L.; writing—review and editing, J.G.; visualization, J.G.; supervision, S.T.; project administration, J.G.; funding acquisition, J.G. and S.T. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by National Natural Science Foundation of China, grant number 11572036.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Acknowledgments

The authors give their sincere thanks to the editors and the anonymous reviewers for their constructive comments of the manuscript.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Yin, J.; Yang, Z.; Luo, Y. Adaptive tracking method for non-cooperative continuously thrusting spacecraft. Aerospace 2021, 8, 244. [Google Scholar] [CrossRef]
  2. Wang, S.; Bi, D.; Ruan, H.; Du, M. Radar maneuvering target tracking algorithm based on human cognition mechanism. Chin. J. Aeronaut. 2019, 32, 1695–1704. [Google Scholar] [CrossRef]
  3. Lim, J.; Kim, H.; Park, H. Minimax particle filtering for tracking a highly maneuvering target. Int. J. Robust Nonlinear Control 2020, 30, 636–651. [Google Scholar] [CrossRef]
  4. Cheng, Y.; Yan, X.; Tang, S.; Wu, M.; Li, C. An adaptive non-zero mean damping model for trajectory tracking of hypersonic glide vehicles. Aerosp. Sci. Technol. 2021, 111, 106529. [Google Scholar] [CrossRef]
  5. Liu, J.; Wang, Z.; Xu, M. DeepMTT: A deep learning maneuvering target-tracking algorithm based on bidirectional LSTM network. Inf. Fusion 2020, 53, 289–304. [Google Scholar] [CrossRef]
  6. Zhu, W.; Xu, Z.; Li, B.; Wu, Z. Research on the observability of bearings-only target tracking based on multiple sonar sensors. In Proceedings of the 2012 Second International Conference on Instrumentation, Measurement, Computer, Communication and Control (IMCCC), Harbin, China, 8–10 December 2012. [Google Scholar]
  7. Jia, S.; Zhang, Y.; Wang, G. Highly maneuvering target tracking using multi-parameter fusion Singer model. J. Syst. Eng. Electron. 2017, 28, 841–850. [Google Scholar] [CrossRef]
  8. Jiang, B.; Sheng, W.; Zhang, R.; Han, Y.; Ma, X. Range tracking method based on adaptive “current” statistical model with velocity prediction. Signal Process. 2017, 131, 261–270. [Google Scholar] [CrossRef]
  9. Blom, H.; Bar-Shalom, Y. The interacting multiple model algorithm for systems with Markovian switching coefficients. IEEE Trans. Autom. Control 1988, 33, 780–783. [Google Scholar] [CrossRef]
  10. Lim, J.; Kim, H.; Park, H. Interactive-multiple-model algorithm based on minimax particle filtering. IEEE Signal Process. Lett. 2020, 27, 36–40. [Google Scholar] [CrossRef]
  11. Wang, M.; Bai, Y. Multi-platform maneuvering target tracking based on BLUE-AIMM-CI algorithm. In Proceedings of the 34th Chinese Control Conference, Hangzhou, China, 28–30 July 2015. [Google Scholar]
  12. Ding, Z.; Liu, Y.; Liu, J.; Yu, K.; You, Y.; Jing, P.; He, Y. Adaptive interacting multiple model algorithm based on information-weighted consensus for maneuvering target tracking. Sensors 2018, 18, 2012. [Google Scholar] [CrossRef] [Green Version]
  13. Yu, M.; Chen, W.; Chambers, J. State dependent multiple model-based particle filtering for ballistic missile tracking in a low-observable environment. Aerosp. Sci. Technol. 2017, 67, 144–154. [Google Scholar] [CrossRef] [Green Version]
  14. Li, X.; Jilkov, V.; Ru, J. Multiple-model estimation with variable structure part VI: Expected-mode augmentation. IEEE Trans. Aerosp. Electron. Syst. 2005, 41, 853–867. [Google Scholar]
  15. Wang, J.; Dong, P.; Jing, Z.; Cheng, J. Consensus variable structure multiple model filtering for distributed maneuvering tracking. Signal Process. 2019, 162, 234–241. [Google Scholar] [CrossRef]
  16. Yu, M.; Oh, H.; Chen, W. An improved multiple model particle filtering approach for maneuvering target tracking using airborne GMTI with geographic information. Aerosp. Sci. Technol. 2016, 52, 62–69. [Google Scholar] [CrossRef] [Green Version]
  17. Gelb, A. Applied Optimal Estimation; MIT Press: Cambridge MA, USA, 1974. [Google Scholar]
  18. Kim, J.; Lee, K. Unscented Kalman filter-aided long short-term memory approach for wind nowcasting. Aerospace 2021, 8, 236. [Google Scholar] [CrossRef]
  19. Wan, E.A.; van der Merwe, R. The unscented Kalman filter for nonlinear estimation. In Proceedings of the IEEE 2000 Adaptive Systems for Signal Processing, Communications, and Control Symposium (Cat. No.00EX373), Lake Louise, AB, Canada, 1–4 October 2000. [Google Scholar]
  20. Zhong, Z.; Zhao, E.; Zheng, X.; Zhao, X. A consensus-based square-root cubature Kalman filter for maneuvering target tracking in sensor networks. Trans. Inst. Meas. Control 2020, 42, 3052–3062. [Google Scholar] [CrossRef]
  21. Zhou, D.; Xi, Y.; Zhang, Z. Suboptimal fading extended Kalman filtering for nonlinear systems. Control Decis. 1990, 5, 1–6. [Google Scholar]
  22. Zhou, D.; Xi, Y.; Zhang, Z. A suboptimal multiple fading extended Kalman filter. Acta Autom. Sin. 1991, 17, 689–695. [Google Scholar]
  23. Liu, Q.; Huang, C.; Li, P. Distributed consensus strong tracking filter for wireless sensor networks with model mismatches. Int. J. Distrib. Sens. Netw. 2017, 13, 1–10. [Google Scholar] [CrossRef] [Green Version]
  24. Hu, G.; Gao, D.; Zhong, Y.; Subic, A. Modified strong tracking unscented Kalman filter for nonlinear state estimation with process model uncertainty. Int. J. Adapt. Control Signal Process. 2015, 29, 1561–1577. [Google Scholar] [CrossRef]
  25. Xia, B.; Wang, H.; Wang, M.; Sun, W.; Xu, Z.; Lai, Y. A new method for state of charge estimation of lithium-ion battery based on strong tracking cubature Kalman filter. Energies 2015, 8, 13458–13472. [Google Scholar] [CrossRef] [Green Version]
  26. Li, J.; Zhao, R.; Chen, J.; Zhao, C.; Zhu, Y. Target tracking algorithm based on adaptive strong tracking particle filter. IET Sci. Meas. Technol. 2016, 10, 704–710. [Google Scholar]
  27. Zhang, A.; Bao, S.; Gao, F.; Bi, W. A novel strong tracking cubature Kalman filter and its application in maneuvering target tracking. Chin. J. Aeronaut. 2019, 32, 2489–2502. [Google Scholar] [CrossRef]
  28. Liu, H.; Wu, W. Strong tracking spherical simplex-radial cubature Kalman filter for maneuvering target tracking. Sensors 2017, 17, 741. [Google Scholar] [CrossRef] [Green Version]
  29. Li, Z.; Yang, W.; Ding, D. A novel fifth-degree strong tracking cubature Kalman filter for two-dimensional maneuvering target tracking. Math. Probl. Eng. 2018, 2018, 5918456. [Google Scholar] [CrossRef]
  30. Wang, J.; Zhang, T.; Xu, X.; Li, Y. A variational Bayesian based strong tracking interpolatory cubature Kalman filter for maneuvering target tracking. IEEE Access 2018, 6, 52544–52560. [Google Scholar] [CrossRef]
  31. Zhang, H.; Xie, J.; Ge, J.; Lu, W.; Liu, B. Strong tracking SCKF based on adaptive CS model for maneuvering aircraft tracking. IET Radar Sonar Navig. 2018, 12, 742–749. [Google Scholar] [CrossRef]
  32. Ma, J.; Guo, X. Combination of IMM algorithm and ASTRWCKF for maneuvering target tracking. IEEE Access 2020, 8, 143095–143103. [Google Scholar] [CrossRef]
  33. Jiang, Y.; Ma, P.; Baoyin, H. Residual-normalized strong tracking filter for tracking a noncooperative maneuvering spacecraft. J. Guid. Control Dyn. 2019, 42, 2304–2309. [Google Scholar] [CrossRef]
  34. Gao, W.; Li, J.; Zhou, G.; Li, Q. Adaptive Kalman filtering with recursive noise estimator for integrated SINS/DVL systems. J. Navig. 2015, 68, 142–161. [Google Scholar] [CrossRef]
  35. Huang, Y.; Zhang, Y.; Wu, Z.; Li, N.; Chambers, J. A novel adaptive Kalman filter with inaccurate process and measurement noise covariance matrices. IEEE Trans. Autom. Control 2018, 63, 594–601. [Google Scholar] [CrossRef] [Green Version]
  36. Ge, B.; Zhang, H.; Jiang, L.; Li, Z.; Butt, M. Adaptive unscented Kalman filter for target tracking with unknown time-varying noise covariance. Sensors 2019, 19, 1371. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  37. Fang, X.; Chen, L. Noise-aware maneuvering target tracking algorithm in wireless sensor networks by a novel adaptive cubature Kalman filter. IET Radar Sonar Navig. 2020, 14, 1795–1802. [Google Scholar] [CrossRef]
  38. Fang, W.; Jiang, J.; Lu, S.; Gong, Y.; Tao, Y.; Tang, Y.; Yan, P.; Luo, H.; Liu, J. A LSTM algorithm estimating pseudo measurements for aiding INS during GNSS signal outages. Remote Sens. 2020, 12, 256. [Google Scholar] [CrossRef] [Green Version]
  39. Wu, F.; Luo, H.; Jia, H.; Zhao, F.; Xiao, Y.; Gao, X. Predicting the noise covariance with a multitask learning model for Kalman filter-based GNSS/INS integrated navigation. IEEE Trans. Instrum. Meas. 2021, 70, 8500613. [Google Scholar] [CrossRef]
  40. Hu, L.; Tang, Y.; Zhou, Z.; Pan, W. Reinforcement learning for orientation estimation using inertial sensors with performance guarantee. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021. [Google Scholar]
  41. Tang, Y.; Hu, L.; Zhang, Q.; Pan, W. Reinforcement learning compensated extended Kalman filter for attitude estimation. In Proceedings of the International Conference on Intelligent Robots and Systems (IROS), New York, NY, USA, 27 September–1 October 2021. [Google Scholar]
  42. Gao, X.; Luo, H.; Ning, B.; Zhao, F.; Bao, L.; Gong, Y.; Xiao, Y.; Jiang, J. RL-AKF: An adaptive Kalman filter navigation algorithm based on reinforcement learning for ground vehicles. Remote Sens. 2020, 12, 1704. [Google Scholar] [CrossRef]
  43. Liu, Y.; Wang, X.; Liu, K. Network anomaly detection system with optimized DS Evidence Theory. Sci. World J. 2014, 753659, 1–14. [Google Scholar] [CrossRef]
  44. Wang, Y.; Li, X. Distributed estimation fusion with unavailable cross-correlation. IEEE Trans. Aerosp. Electron. Syst. 2012, 48, 259–278. [Google Scholar] [CrossRef]
  45. Henderson, P.; Islam, R.; Bachman, P.; Pineau, J.; Precup, D.; Meger, D. Deep reinforcement learning that matters. In Proceedings of the Thirty-Second AAAI Conference on Artificial Intelligence, New Orleans, LA, USA, 2–7 February 2018. [Google Scholar]
  46. Li, B.; Gan, Z.; Chen, D.; Sergey Aleksandrovich, D. UAV maneuvering target tracking in uncertain environments based on deep reinforcement learning and meta-learning. Remote Sens. 2020, 12, 3789. [Google Scholar] [CrossRef]
Figure 1. The framework of the noise-adaption EKF.
Figure 1. The framework of the noise-adaption EKF.
Sensors 22 05389 g001
Figure 2. The basic framework of DDPG.
Figure 2. The basic framework of DDPG.
Sensors 22 05389 g002
Figure 3. The implementation framework of the process noise adaption based on DDPG.
Figure 3. The implementation framework of the process noise adaption based on DDPG.
Sensors 22 05389 g003
Figure 4. The structure of actor network.
Figure 4. The structure of actor network.
Sensors 22 05389 g004
Figure 5. Estimated trajectories.
Figure 5. Estimated trajectories.
Sensors 22 05389 g005
Figure 6. Position estimations errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of THE elevation angle.
Figure 6. Position estimations errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of THE elevation angle.
Sensors 22 05389 g006
Figure 7. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Figure 7. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Sensors 22 05389 g007
Figure 8. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Figure 8. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Sensors 22 05389 g008
Figure 9. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Figure 9. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Sensors 22 05389 g009
Figure 10. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Figure 10. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Sensors 22 05389 g010
Figure 11. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Figure 11. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Sensors 22 05389 g011
Figure 12. Position estimations errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of the elevation angle.
Figure 12. Position estimations errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of the elevation angle.
Sensors 22 05389 g012
Figure 13. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Figure 13. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Sensors 22 05389 g013
Figure 14. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Figure 14. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Sensors 22 05389 g014
Figure 15. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Figure 15. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Sensors 22 05389 g015
Figure 16. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Figure 16. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Sensors 22 05389 g016
Figure 17. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Figure 17. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Sensors 22 05389 g017
Figure 18. Estimated trajectories.
Figure 18. Estimated trajectories.
Sensors 22 05389 g018
Figure 19. Position estimation errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of the elevation angle.
Figure 19. Position estimation errors. (a) Estimation errors of the range; (b) Estimation errors of the azimuth angle; (c) Estimation errors of the elevation angle.
Sensors 22 05389 g019
Figure 20. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Figure 20. σ -Boundary of position estimation errors. (a) σ -Boundary of the range; (b) σ -Boundary of the azimuth angle; (c) σ -Boundary of the elevation angle.
Sensors 22 05389 g020
Figure 21. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Figure 21. Velocity estimation errors. (a) Estimation errors of v x ; (b) Estimation errors of v y ; (c) Estimation errors of v z .
Sensors 22 05389 g021
Figure 22. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Figure 22. σ -Boundary of velocity estimation errors. (a) σ -Boundary of v x ; (b) σ -Boundary of v y ; (c) σ -Boundary of v z .
Sensors 22 05389 g022
Figure 23. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Figure 23. Acceleration estimation errors. (a) Estimation errors of a x ; (b) Estimation errors of a y ; (c) Estimation errors of a z .
Sensors 22 05389 g023
Figure 24. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Figure 24. σ -Boundary of acceleration estimation errors. (a) σ -Boundary of a x ; (b) σ -Boundary of a y ; (c) σ -Boundary of a z .
Sensors 22 05389 g024
Table 1. Neural network settings.
Table 1. Neural network settings.
LayersActor NetworkCritic Network
Input layer34
Hidden layer 1128128
Hidden layer 2128128
Output layer11
Table 2. Simulation parameters of DDPG.
Table 2. Simulation parameters of DDPG.
ParametersValue
The discounting factor ξ 0.99
The updating rate τ 0.001
The number of samples N s a m p l e 64
The number of episodes500
The number of timesteps1000
Table 3. Sinusoidal parameters.
Table 3. Sinusoidal parameters.
Directions x y z
A 121
ω 0.0050.010.005
φ 0 303030
Table 4. Measurement accuracy of multiple sensors.
Table 4. Measurement accuracy of multiple sensors.
Sensors σ r ( m ) σ β ( o ) σ ε ( o )
S 1 100.010.01
S 2 50.020.02
S 3 100.020.02
Table 5. Estimation errors of the range (m).
Table 5. Estimation errors of the range (m).
SensorsIMMSTFRNSTFAKFNAEKF
S 1 15.745417.528517.472796.180814.4525
S 2 4.83723.97453.98163.85603.8291
S 3 8.90038.10248.12087.6047.3634
Fusion4.75368.19888.4076129.23553.5371
Table 6. Estimation errors of the azimuth angle (°).
Table 6. Estimation errors of the azimuth angle (°).
SensorsIMMSTFRNSTFAKFNAEKF
S 1 0.00730.00980.00980.01160.0057
S 2 0.01100.01300.01330.00880.0090
S 3 0.01010.01350.01390.00990.0087
Fusion0.00520.00760.00770.01080.0043
Table 7. Estimation errors of the elevation angle (°).
Table 7. Estimation errors of the elevation angle (°).
SensorsIMMSTFRNSTFAKFNAEKF
S 1 0.00760.01000.00980.42930.0060
S 2 0.01080.01400.01360.00970.0097
S 3 0.01020.01450.01390.03280.0094
Fusion0.00510.00760.00740.17900.0043
Table 8. Computing time (s).
Table 8. Computing time (s).
IMMSTFRNSTFAKFNAEKF
1.96451.73431.81733.30551.8572
Table 9. Maneuver parameters of the target.
Table 9. Maneuver parameters of the target.
Time (s) Acceleration   ( m / s 2 ) Time (s) Acceleration   ( m / s 2 )
xyzxyz
0–60000480–5402.5−52.5
60–120−22.518−22.5540–600−12.524−12.5
120–1802.5−102.5600–6602.5−142.5
180–240−15−15−15660–7207.5−107.5
240–3004.5−104.5720–780−910−9
300–360−2029−20780–840−5.511−5.5
360–420−10−8−10840–9004.5−94.5
420–480−12.5−10−12.5900–10002.5−122.5
Table 10. Estimation errors of the range (m).
Table 10. Estimation errors of the range (m).
SensorsIMMSTFRNSTFNAEKF
S 1 18.249118.091018.200317.4784
S 2 5.00145.20045.24744.6219
S 3 9.45259.20299.31688.6291
Fusion4.953211.833412.03104.8331
Table 11. Estimation errors of the azimuth angle (°).
Table 11. Estimation errors of the azimuth angle (°).
SensorsIMMSTFRNSTFNAEKF
S 1 0.00620.00980.00990.0064
S 2 0.01100.01370.01430.0104
S 3 0.01170.01330.01360.0096
Fusion0.00480.00790.00800.0047
Table 12. Estimation errors of the elevation angle (°).
Table 12. Estimation errors of the elevation angle (°).
SensorsIMMSTFRNSTFNAEKF
S 1 0.00620.00930.00920.0057
S 2 0.01020.01410.01370.0107
S 3 0.01120.01340.01310.0098
Fusion0.00500.00760.00740.0045
Table 13. Computing time (s).
Table 13. Computing time (s).
IMMSTFRNSTFNAEKF
1.99201.69581.80961.8723
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Li, J.; Tang, S.; Guo, J. Noise-Adaption Extended Kalman Filter Based on Deep Deterministic Policy Gradient for Maneuvering Targets. Sensors 2022, 22, 5389. https://doi.org/10.3390/s22145389

AMA Style

Li J, Tang S, Guo J. Noise-Adaption Extended Kalman Filter Based on Deep Deterministic Policy Gradient for Maneuvering Targets. Sensors. 2022; 22(14):5389. https://doi.org/10.3390/s22145389

Chicago/Turabian Style

Li, Jiali, Shengjing Tang, and Jie Guo. 2022. "Noise-Adaption Extended Kalman Filter Based on Deep Deterministic Policy Gradient for Maneuvering Targets" Sensors 22, no. 14: 5389. https://doi.org/10.3390/s22145389

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

Article Metrics

Back to TopTop