Video

1 downloads 0 Views 370KB Size Report
an on-board video camera and a ground-based radar sensor to track the ... and x. T. := [. xT. vT. ] . The kinematics of the missile and target are defined by. ˙x. M.
Precision Missile Guidance using Radar/Video Sensor Fusion with a Communication Constraint 1 Veerachai Malyavej, Ian R. Manchester, Andrey V. Savkin School of Electrical Engineering and Telecommunications, University of New South Wales, Sydney 2052, Australia, [email protected], [email protected], [email protected]. Abstract We apply recent results in state estimation over limited-capacity communication channels to a precision missile guidance problem. In the situation considered, the missile has a video camera on-board, and receives data from a ground-based radar. A constructive sensor fusion algorithm is presented which allows for very restrictive bit-rate constraints on the data sent from ground station to missile. The Circular Navigation Guidance law is used to guide the missile. There are two forms of this law: one which requires angular information only, and a more precise version which requires full state information. Sensor fusion allows us to construct the more accurate version. Simulations were run to compare performance with and without the transmitted data, and their results show strong benefits in the use of sensor fusion.

1 Introduction There is currently a great deal of interest in utilizing modern systems and control theory to improve performance of target-tracking and missile-guidance systems. The ability to combine information from several independent sensor platforms, such as ground based radars and autonomous aerial vehicles, with that available from on-board sensors is one very promising area, see [1] for example. In this paper we present a precision guidance law which uses both an on-board video camera and a ground-based radar sensor to track the target. Both sensors have measurement noise, and the communication channel between the ground station and the missile suffers very restrictive bit-rate constraints. The main motivating advantages of video cameras are that they are comparatively cheap, and very accurate at close ranges. However, at long ranges it may be impossible to resolve the target, and atmospheric effects such as fog or cloud will obviously 1 This

Council.

work was supported by the Australian Research

cause problems. Furthermore, video cameras only provide angular information, and not range information without further processing. We take advantage of recent research in the area of state estimation over limited-capacity communication channels to enrich the missile’s information with transmissions from a ground-based radar. We use Circular Navigation Guidance (CNG), a precision guidance law introduced in [2–4]. This law can be calculated using angular information only, and so can be used with a video camera alone. It can, of course, also be calculated with full state information, so we can compare performance with and without sensor fusion. A brief schematic of the procedure can be given with reference to the picture in Figure1. The groundbased radar measures the target’s position, suffering some measurement noise, and sends a quantized approximation of this information to the missile using an algorithm similar to those in [5, 6]. The missile itself measures angular information, also with some error. These two measurements are nonlinearly related, and can be combined with a nonlinear setvalued state estimator, the robust extended Kalman filter (REKF) [7, 8]. This state estimate is then used to calculate the CNG guidance command, hopefully resulting in a successful intercept. The structure of the paper is as follows: Section 2 holds a precise mathematical statement of the problem, then in Section 3 the basics of CNG are presented. In Section 4 we discuss measurement models and sensor fusion with the REKF, followed by the coder-decoder system in Section 5. Results of a few simulations comparing performance with and without sensor fusion are given in Section 6. Some brief conclusions are then given to sum up the results.

2 Problem Statement We consider a simple kinematic model of the missiletarget engagement. Let xM , vM ∈ R3 be the position and velocity of the missile in 3-dimensional

2QERDUG0LVVLOH

6HQVRU)XVLRQ 5(.)

'HFRGHU

|P



2QERDUG 9LGHR&DPHUD

7DUJHWSRVLWLRQ

0LVVLOHDQG7DUJHW (QJDJHPHQW 6\VWHP

*XLGDQFH/DZ

k

k %LWUDWHFRQVWUDLQW&KDQQHO

|U

&RGHU

|

0LVVLOHWUDMHFWRU\

ª |P º « U» ¬« | ¼»

/26

5HPRWH5DGDU 6HQVLQJ

0LVVLOHLQLWLDO SRVLWLRQ

*URXQGEDVHG6WDWLRQ

Figure 2: Two-Dimensional Geometry of CNG

Figure 1: Framework block diagram space also xT , vT ∈ R3 be the position and velocity of the target in 3-dimensional space.  Let   xM := xM vM and xT := xT vT . The kinematics of the missile and target are defined by

and

x˙ M = AM xM + Bu

(1)

x˙ T = AT xT + Bw

(2)

where u and w are the acceleration input to the missile and target respectively and     03×3 03×3 I3×3 , B= . AM = AT = 03×3 03×3 I3×3 A new system can be defined in terms of the relative position, denoted xR , of the missile and target: xR = xT − xM . Now let a vector x(t) ∈ R9 be defined   . It is obvious that the as x (t) := xR vM vT dynamics of this system can be described by x˙ (t) = Ax (t) + B1 u (t) + B2 w (t) where ⎡

03 A = ⎣ 03 03

−I3 03 03

(3)

⎤ ⎤ ⎤ ⎡ ⎡ I3 03 03 03 ⎦ , B1 = ⎣ I3 ⎦ , B2 = ⎣ 03 ⎦ . 03 03 I3

We assume that the missile is only able to accelerate orthogonal to its current velocity, i.e. rotate its heading. Thus this control signal are subject the con straint: u (t) vM (t) = 0, ∀t. We can treat the w (t) as the uncertainty of the system. Our objective in precision missile guidance is to design a controller that not only brings the missile as close as possible to the target but does so with a certain terminal geometry, i.e. the missile approaches the target with a certain prescribed heading. To state this precisely, we must first introduce some notation. For any vector Γ, Φ we define the Angle between two vectors as

Γ Φ −1 Angle (Γ, Φ) := cos Γ Φ Let vF ∈ R3 denotes the desired final velocity vector. Then our aim is to design the controller of the form u (t) = f (x (t) , vF )

(4)

, such that: xR (Tf ) → min Angle(vM , vF ) → min for some finite time Tf .

and

Definition 1 A target intercept is said to be perfect if there exists some finite time Tf such that xR (Tf ) = 0, Angle(vM , vF ) = 0.

3 Circular Navigation Guidance In this section, we present the idea of the CNG originally published in [2]. It is better to describe the concept of CNG in the two-dimensional plane rather than in three-dimensional sphere. Nevertheless, we will extend this idea to three-dimensional sphere later. The general concept of CNG can be described by Figure 2. According to the Figure 2, we define the following parameters and notation: λ := Angle (vM , xR ) , γ := Angle (xR , vF ) . For any vector Γ, Φ we define the projection operator as (Φ Γ) Γ ProjΓ Φ := 2 Γ where · denote standard Euclidean norm. We now present the main theory of CNG published in [2]. Theorem 2 Consider the case of a stationary target. Introduce the circle uniquely defined by following properties: (i) The initial position of the missile lies on the circle. (ii) The position of the target lies on the circle. (iii) The desired final velocity vector at the target’s position is a tangent to the circle. Suppose that a controller of the form (4) is designed such that the angles λ (t) and γ (t) are kept exactly equal over the full flight time, then the missile’s trajectory will be the arc on this circle. Furthermore, this will result in a perfect intercept.

In order to navigate the missile to keep on the trajectory defined by Theorem 2, we must keep the angle λ (t) and γ (t) equal. Indeed, this can be viewed as the tracking problem. For more general in threedimensional space, we define the desired velocity vector as (5) vD := 2ProjxR vF − vF . This vector is the reflection of the desired final velocity vector vF about the line of sight. Then, to follow the trajectory from the Theorem 2, the direction of missile velocity, vM , must track the direction of desired velocity, vD . More precisely, let us define the angle error as eλ := Angle (vD , vM ) .

(6)

Then, we can simply use the proportional control law: (7) u ˜ = kp eλ where kp is a given controller gain. However, this control signal can only be applied in a direction orthogonal to the missile velocity, i.e. turning command. Thus, we compute a unit vector, denoted by uD , representing the direction of the turning command. This is the normalized projection of vD onto the subspace orthogonal to vM as follows: vD − ProjvM vD uD1 := vD − Projv vD . M

(8)

Hence the final control signal can be written as u := u ˜p uD1 = kp eλ uD1 .

(9)

This controller form is suitable when we can measure the angle only. Thus, it can be use with information from the video camera only. The controller presented above gives a good result to stationary target. If target is moving, the angle error in (6) will be affected, see [2]. If we know vT , however, we can counteract this in a way similar to that used in [2] by introducing an offset to vD . The detail for obtaining this offset in two-dimensional plane can be found in [2]. We now denote the angle between target velocity and relative position as: ψ = Angle(vT , xR ). Then, we calculate the offset angle as   −1 vT  λo = 2 sin sin ψ . vm 

(10)

(11)

To add this offset to vD , we define the rotation vector =

vD × vT . vD  vT 

(12)

Here × denotes cross product of two vectors. Then we compute the new desired velocity vector as below: vˆD = vD + λo ( × vD ) .

(13)

Then we can replace the desired vector vD by vˆD in (6)-(9) to obtain the new control signal. Because this control signal requires knowledge of vT , we can only use it when we have combination of radar and video camera measurement.

4 Measurement equation This section details the two sources of information available to the missile: the video camera and the ground-based radar. We consider each as a “system output”, corrupted by some noise, and give equations representing their relationship with the system model. A filter is then designed to fuse their data into a state estimate. The measurements from the video camera are nonlinearly related to the system state, so we must use a nonlinear filter for data fusion. Equations are given for a nonlinear set-valued state estimator. These equations are not tractable for online computation, so a more pragmatic filter is obtained by approximating general sets as ellipsoids, and by linearizing the system dynamics at each step. The robust extended Kalman filter (REKF) thus obtained is similar in form to the standard extended Kalman filter, but allows for a wider class of uncertainty. Also, it gives set-valued estimates, rather than a statistical description. 4.1 Measurement equation from video camera on missile We assume that the video camera on the missile is simple pinhole camera, located a fixed distance f in front of the image plane (see Figure 3), for more details see [9]. The position of the target in image plane has the coordinates (x1 , x2 ) . We now consider the coordinate transformation from Cartesian to spherical. Notation 3 Let (i, j, k) be the unit vector in Cartesian space and (r, θ, φ) be the coordinates in spherical space. Then we define T : (i, j, k) → (r, θ, φ) as follow: i2 + j 2 + k 2 , r =

j , θ = tan−1 i 

i2 + j 2 −1 . φ = tan k

where vˇ is the measurement noise.

7DUJHW

Now we combine the measurement equation in (14) with the information from the camera on the missile. That is     yˇ (t) vˇ y : = + y¯ (t) v¯ ⎤   ⎡ tan−1 xx21 (t) (t) ⎢ √

⎥ ⎥ ⎢ x1 (t)2 +x2 (t)2 = ⎢ tan−1 ⎥ + v (t) .(16) x3 ⎦ ⎣ ¯ Cx (t)

/HQV

k

i

,PDJH j

Figure 3: Geometry of image plane from on-board video camera

Now consider the situation in Figure 3. It is obvious that with given target coordinates on the image plane (x1 , x2 ), the two angles ∆θ and ∆φ can be computed as follow: ∆θ = sin−1 xf1 , ∆φ = sin−1 √ x22 2 . Acx1 +f

cording to the Figure 3, we assume that the velocity of the missile can be obtained. Consequently, by using the transformation T we have two angles θ1 , φ1 . Then the angles θ2 , φ2 of the vector xR can be obtained by θ2 = θ1 +∆θ and φ2 = φ1 +∆φ. Because we cannot measure the range of the xR , we now define vector x ˇR := (r2 , θ2 , φ2 ) where r2 = x21 + x22 + f 2 . It is clear that this vector is colinear with xR or x ˇR = δxR , for some scalar δ > 0. Since the CNG law (9) requires angle only, the vector x ˇR can be utilized successfully by transform back to Cartesian space by T −1 . 4.2 Sensor fusion Now we consider the combination of the information from on-board video camera and the information from ground-based radar. Let y¯ (t) denote the measured output from the ground-based radar via the channels with Coder-Decoder scheme that will be presented in the next section. We assume that this measurement equation gives the full state, i.e. xR , vM , vT , corrupted with some noise. Therefore, we have that ¯ (t) + v¯ y¯ (t) = Cx

Then by using this measurement equation, there exist some non-linear relationship. Moreover, we consider the noise v (t) as the combination of the measurement noise with some uncertainty noise that depends on the system state. This allows some uncertainty of the sensing system. 4.3 Set-valued state estimation for non-linear uncertain systems We now convert the system in (3) and measurement equation of the form (16) to general non-linear uncertain system as:

where C¯ = [I9×9 ] and v¯ is the noise coming from radar measurement plus the noise from channels. We have, form previous subsection, the two angles of vector xR ,i.e. (θ2 , φ2 ). Therefore, from the coordinate transformation T , we define the measurement equation from those angles as 

yˇ (t) := [θ2 , φ2 ] + vˇ

 

x21 + x22 x2 −1 −1 , tan + vˇ. = tan x1 x3 (15)

A (x, u) + B2 w

z y

K (x, u) C(x) + v.

= =

(17)

Here x (t) ∈ Rn denotes the state of the system, y (t) ∈ Rl is the measured output and z (t) ∈ Rq is the uncertainty output. Also, u (t) is the known control input. Then we treat the disturbance or system noise w (t) and measurement noise v (t) as the uncertainty input. We assume that all of the function in (17) are with continuous and bounded partial derivatives. The uncertainty in the system is defined by the following nonlinear integral constraint, see [8] for more detail:  s  s Φ (x (0))+ L1 (w (t) , v (t)) dt ≤ d+ L2 (z (t)) dt, 0

(14)

x˙ =

0

(18) where d ≥ 0 is a positive real number. Here, Φ (·) , L1 (·) , L2 (·) are bounded non-negative functions with continuous partial derivatives satisfying growth conditions of the type φ (x) − φ (x∗ ) ≤  (1 + x + x∗ ) x − x∗  (19) where · denotes standard Euclidean norm with  > 0, and φ = Φ, L1 , L2 . Uncertainty inputs w (·) , v (·) satisfying this condition are called admissible uncertainties. We consider the problem of characterizing the set of all possible states Xs of the system (17) at time s ≥ 0 which are consistent with a given

control input u0 (·) and a given output path y 0 (·) ; i.e., x ∈ Xs if and only if there exists admissible uncertainties such that if u0 (t) is the control input and x (·) and y (·) are resulting trajectories, then x (s) = x and y (t) = y 0 (t) , for all 0 ≤ t ≤ s. 4.4 The state estimator The state estimation set Xs is characterized in terms of level sets of the solution V (x, s) of the PDE with V (·, 0) = Φ      ∂ V + maxm ∇x V. A x, u0 + B2 w w∈R ∂t  (20)      0 0 = 0. − L1 w, y − C (x) + L2 K x, u The PDE (20) can be viewed as a filter, taking observations u0 (t) , y 0 (t) , 0 ≤ t ≤ s and producing the set Xs as a output. The set of this filter is the function V (·, s) thus V is an information state for the state estimation problem. Theorem 4 Assume the uncertain system (17), (18) satisfies the assumptions given above. Then the corresponding set of possible states is given by Xs = {x ∈ Rn : V (x, s) ≤ d} , where V (x, t) is the unique viscosity solution of (20) in C (Rn × [0, s]) . Proof:

See [8] for proof.

4.5 Robust Extended Kalman Filter More practically, we now consider an approximation of the PDE (20), which leads to a Kalman filter like characterization of the set Xs . Also, we consider the uncertain system (17) and the integral quadratic constraint of the form  1 s   w (t) Qw (t) (x (0) − x0 ) P0 (x (0) − x0 ) + 2 0

 1 s   z (t) z (t) dt. + v (t) Rv (t) dt ≤ d + 2 0 (21) where P0 , Q, R are the symmetric positive definite weighting matrices in suitable dimension. Then, for the system (17) with constraint (21), the PDE (20) can be written as  1  ∂ V + ∇x V. Ax, u0 + ∇x V B2 Q−1 B2 ∇x V  ∂t 2   0  1 0 y − C (x) R y − C (x) − 2    1  + K x, u0 K x, u0 = 0, 2 

V (x, 0) = (x (0) − x0 ) P0 (x (0) − x0 ) .

(22)

Now, from our original system in (3) with measurement equation of the form (16) we have that   A x, u0 = Ax + B1 u. (23) Moreover we consider the uncertainty output  z (t) as the linear function of the state x, i.e. K x, u0 = Kx. Therefore, system (17) corresponding to (23) and above uncertainty output and with constraint (21), the PDE (20) can be approximated by the following Riccati with P (0) = P0 and estimated system equation: P˙ + A P + P A + P B2 Q−1 B2 P − Cx˜ RCx˜ + K  K = 0, (24) ·    0  −1 x ˜ (t) = A˜ x (t)+B1 u (t)+P (t) Cx˜ R y − C (˜ x (t)) (25) x (t)) . Then, the function V (x, t) where Cx = ∇x˜ C (˜ was approximated by V˜ (x, t) of the form 1  ˜ (t)) + φ (t) , V˜ (x, t) = (x − x ˜ (t)) P (t) (x − x 2 (26) where      1 t  0 y − C (˜ φ (t) := x) R y 0 − C (˜ x) − K  K dτ. 2 0 Hence, it follows from Theorem 4 that an approximate formula for the set Xs is given by  1  ˜ (s)) Xs = x ∈ Rn : (x − x ˜ (s)) P (s) (x − x 2  ≤ d − φ (s) .

5 Coder-Decoder In this section we develop the coder-decoder scheme which encodes the information gathered at the ground-based tracking station into a sequence of codewords. This allows us to reconstruct this state estimate on board the missile (albeit with some quantization error). In this framework, we assume that the channel is a noiseless and there is no time delay in transmission, however there is a finite number of bits which can be transmitted per unit of time. We assume that the radar can measure the position of both missile and target, but has some bounded measurement noise. Because the ground-based radar cannot access the missile’s control signal or the target’s acceleration,we treat these as disturbances. However, we assume that we can estimate upper bounds on the disturbance energy. These bounds on disturbances and measurement noise are treated with the methods of Integral Quadratic Constraints (IQCs), see [8, 10].

The quantization method we employ is similar to that presented in [5, 6]. The essential procedure is to have identical state estimators running both at the ground station and on board the missile. The ground station, which is receiving radar information, can then send corrections to the missile. The methods in those papers cannot be applied verbatim, however. This is because they work by quantizing the set of possible states, which must be bounded. Our system, being essentially a pair of double integrators, is unstable, so the set of all possible states will thus rapidly increase in measure as time goes on. We detour around the problem by instead coding the difference between the measured positions and estimated positions. Since the system is observable from the radar measurements, this signal is uniformly bounded for all time. The quantizing scheme is very simple: the bound on the signal measurement difference signal is ellipsoidal, we calculate a hypercube bound of this ellipsoid, and quantize this hypercube uniformly into smaller hypercubes (of which there are finitely many), and each is assigned particular symbol. The symbol corresponding to the particular hypercube the signal lies in is transmitted to the missile, which infers from it the centroid of the hypercube. The centroid is used as measurement error feedback to the state estimators at both ends of the transmission channel, so that they remain equal. In each transmission packet, the number of admissible codewords (and hence quantization hypercubes) is N = 2m where m is the number of bits that our channel can send per transmission interval. Now consider the missile and target system in (1),(2) with discrete measurement equation: x˙ (t) = Ax (t) + B w ˜ (t) y (kT ) = Cx (kT ) + v (kT )

(27)

where

the target as 



(x (0) − x0 ) S0 (x (0) − x0 ) +   v (t) Rv (t) dt ≤ d.

Tf



w ˜ (t) Qw ˜ (t) dt+ 0

kT ≤Tf

(28) where S0 , Q, R are given symmetric positive weighting matrices and d is a given number. Then this uncertain system can be classified to the Sum-Integral Quadratic Constraint (SIQC), see [8]. We now, describe the set of all possible states of system (27),(28) as following definition. Definition 5 The discrete-continuous system (27) with SIQC (28) is said to be strictly verifiable on [0, Tf ] , if for any vector x0 ∈ Rn , time s ∈ (0, Tf ], constant d > 0 and measured output y (kT ) = y0 (kT ) , the set Xs [x0 , y0 |s0 , d] is bounded. Notation 6 Let g (t) be a given matrix or vector function, which is right continuous and may be left discontinuous. Then, g (kT − )denotes the value of g (t) just before kT, i.e.,   g kT − := lim g (kT − δ) δ>0,δ→0

assuming the limit exists. The following theorem obtains the complete set Xs [x0 , y0 |s0 , d] . This theorem is the special case for the general uncertain system with discrete and continuous measurement (see [8] ), in which only discrete measurement can be obtained and there is no control input. The solution for above set-valued state estimation with discrete measurement involve the following Riccati differential equation with jumps

=AP (s) + P (s)A + BQ−1 B  , s = kT, −1   −1 + C  RC , k = 1, 2, ..., N. P (kT ) = P kT − P˙ (s)

⎤ ⎡ 03×3 xM ⎢ 03×3 ⎢ xT ⎥ ⎥ ⎢ x (t) := ⎢ ⎣ vM ⎦ , B = ⎣ I3×3 vT 03×3    ˜ (t) = C = I6×6 06×6 , w ⎡

⎤ 03×3 03×3 ⎥ ⎥, 03×3 ⎦ I3×3  u (t) . w (t)

Since the controller is developed on the missile with fused information, the control signal u (t) in this case should be treated as an unknown uncertainty. Also, suppose that we can estimate the energy bound of the uncertainty input w ˜ (t) , measurement noise v (kT ) and the uncertainty of the initial condition of

Such a Riccati equation is referred to as a jump Riccati equation. In addition, we consider the set of state equation .

x ˆ(s) = Aˆ x(s), f or s = kT  − x ˆ (kT ) = x ˆ kT      ˆ kT − , + P kT − C  R y0 (kT ) − C x k = 1, 2, ..., N. Such a state equation is referred to as a jump state equation. The following result was obtained in [8].

Theorem 7 Let S0 = S0 > 0 be a given matrix, and Q = Q and R = R be given matrices such that Q ≥ σI, R ≥ σI where σ > 0. Consider the system (27) and the constraint (28). Then the following statements hold: (i) The system (27), (28) is strictly verifiable on [0, Tf ] if and only if the solution P (·) to the jump Riccati equation (29) with initial condition P (0) = S0−1 exists and is positive-definite on the interval [0, Tf ] (ii) If the system (27), (28) is strictly verifiable, then  Xs [x0 , y0 |s0 , d] = xs ∈ Rn :   −1 ˆ (s)) P (s) (xs − x ˆ (s)) ≤ d − ρs [y0 (·)] (xs − x where ρs [y0 (·)] :=   (y0 (kT ) − C x ˆ (kT )) R (y0 (kT ) − C x ˆ (kT )) . kT ≤s

We are now in a position to develop the CoderDecoder pair to transmit the data from ground-base radar to the missile. The coder and decoder are defined by the following form: Coder:   . (29) h (kT ) = Fk x0 , d, y (·) |kT 0 Decoder: x ˆ (kT ) = Gk (x0 , d, h0 , h1 , ..., hk ) .

(30)

Definition 8 Consider the system (27), (28) with a given d > 0. Let ε > 0 be a given constant, and N > 0 and 0 ≤ N be given integers. The CoderDecoder pair (29), (30) is said to solve the state estimation problem via a digital communication channel with the admissible number of codewords N on the time interval [0, N T ] with the precision level ε if there exist function V (·) : R → R, 0 < V (·) such that x(kT ) − x ˆ(kT )∞ ≤ V (d, ε)

(31)

for all x0 , y (·) , k = 0, 1, 2, ..., N. Here for any vecˆ(kT ) is defined by tor Φ, Φ∞ := maxi {|Φi |} and x (29). In order to develop the estimator in (29) based on quantized data, we simply model the quantizer by adding quantization noise to the signal. That is, let Q denote the quantization function defined by Q (Γ) = Γ + 

(32)

for any vector Γ ∈ Rl with quantization noise  ∈ Rl , which is bounded by precision level. That is, with

precision level ε > 0, ∞ ≤ ε. The quantization process take place in every sampling time T. Thus, we now take the quantization noise into account by modifying the SIQC (28). Note that, as  are bounded, we can directly estimate this energy bound for all k = 1, 2, ..., N by following:    R ≤ l R∞ ε2 := β. (33) k

k

Here ·∞ denote the maximum row sum of the matrix, see page 295 of [11]. We, now define the error between the measured output and estimator output at instant time kT as     ˆ kT − (34) e (kT ) = y kT − − C x where x ˆ (kT ) is defined by (29). This error is required as a control input for estimator to keep tracking the actual system. Also, since we propose to send this information via a limited-capacity communication channel, we now quantize this signal by (32), i.e. e˜ (kT ) := Q (e (kT )) = e (kT ) +          = y kT − +  − C x ˆ kT − = y˜ kT − − C x ˆ kT − . (35) Where y˜ (kT − ) := y (kT − ) +  represent the new set of measured data at time instant kT suffered from quantization noise. To design the Coder-Decoder in the form of (29), (30), we employ the uniform state space quantization. In order to quantize the error of the form (34), let a > 0 be a given constant and consider the  ∆ set Ba = e ∈ Rl : e∞ ≤ a . We propose to quantize each state by the q intervals where q is a specified integer. Therefore, for l dimension state the set Ba will be divided in to q l hypercubes. For each i ∈ {1, 2, ..., l} , we divide the corresponding component of the error vector ei into q intervals as follows:   2a ∆ ; I1i (a) = ei : −a ≤ ei < −a + q   4a 2a ∆ ≤ ei < −a + ; I2i (a) = ei : −a + q q .. .   2a ∆ i Iq (a) = ei : a − (36) ≤ ei ≤ a . q Then for any e(kT ) ∈ Ba , there exist unique integers i1 , i2 , ..., il ∈ {1, 2, ..., q} such that e(kT ) ∈ Ii11 (a) × Ii22 (a) × ... × Iill (a). Also, corresponding to the integers i1 , i2 , ..., il , we define the vector ⎤ ⎡ −a + a(2i1 − 1)/q ⎢ −a + a(2i2 − 1)/q ⎥ ∆ ⎢ ⎥ η¯ (i1 , i2 , ..., il ) = ⎢ (37) ⎥. .. ⎦ ⎣ . −a + a(2il − 1)/q

Indeed, this vector is the center of the hypercubes Ii11 (a) × Ii22 (a) × ... × Iill (a) containing the original point e(kT ).

   

Now we are ready to describe the Coder-Decoder in the form of (29), (30) based on the uniform state space quantization. Coder   ˆ(kT − ); e (kT ) =y kT − − C x h(kT ) = {i1 , i2 , ..., il } for , e(kT ) ∈Ii11 (a) × Ii22 (a) × ... × Iill (a) ⊂ Ba ; e˜(kT ) =¯ η (i1 , i2 , ..., il ) for h(kT ) = {i1 , i2 , ..., il }





























     

)UHTXHQF\RI7DUJHWFRQWUROLQSXW UDGVHF 5DGDUDQG&DPHUD

&DPHUDRQO\

Figure 4: Comparison of miss distance and angle error

.

x ˆ(s) =Aˆ x(s), s = kT  −   x ˆ (kT ) =ˆ x kT + P kT − C  R˜ e(kT ),

Proof: See the full version of this paper for the proof.

f or k =1, 2, ..., N. Decoder e˜(kT ) =¯ η (i1 , i2 , ..., in ) for h(k) = {i1 , i2 , ..., in } .

x ˆ(s) =Aˆ x(s), f or s = kT    − e(kT ), x ˆ (kT ) =ˆ x kT + P kT − C  R˜ f or k =1, 2, ..., N. Here the vector η¯ (i1 , i2 , ..., in ) is defined as in (37). From the Coder-Decoder pair above, with given precision level we must estimate the all possible of quantization area a and then the number of partition of each state q. The final theorem gives the complete solution. Notation 9 Let pij (·) be the corresponding element of the matrix P (·). Then for i = 1, 2, ..., n and k = 0, 1, ..., N we define a constant c > 0 by the following equation   (38) c := max max pii (kT ) k

i

Note that pii (kT ) > 0 for all i, t ≥ 0 because P (t) is positive definite. Notation 10 Let r¯ij be the corresponding element −1 of the matrix √ R . then we define a constant ξ by ξ := maxi r¯ii . Theorem 11 Consider the uncertain system (27), (28). Suppose that this system is strictly verifiable on [0, Tf ] . Let d > 0 , ε > 0 be given constants, N > 0 and 0 ≤ N be given integers. Suppose that √ √  c d+β +ξ d ≤ε (39) q also assume that the quantization noise is uncorrelated to the measured noise. coder-decoder √ Thenthe √ pair (38),(38) with a := c d + β + ξ d solves the state estimation problem via a digital communication channel with the admissible number of codewords N on the time interval [0, N T ] with the precision level ε.

6 Simulation Result We present the simulation results comparing the two sensing methods. For the first one, the CNG law is calculated with data from the video camera only. For the second one, we use sensor fusion to estimate full information. We consider the system with following environment:   Target initial position xT (0) = 5000 1000 0 ,   −5 −2 10 , target initial velocity vT (0) = target control input w = 0.1 cos (ωt), missile   0 0 0 , missile initial position xM (0) =   20 20 20 . We asinitial velocity vM = sume that the initial estimated state is as x0 =   5100 1050 5 20 20 20 −4 −4 8 . The parameters for Robust Extended Kalman Filter, developed on-board, are as follow: Q = 500I3 , ⎤R = ⎡   0 0 I3 0 I2 , P0 = 104 ⎣ 0 100I3 0 ⎦ . 103 0 0.5I6 0 0 I3 Parameters for Hybrid Set-valued Robust Kalman Filter, computed by Coder-Decoder scheme: Q = 100I6 , R = I6 , S0 = 100I12 .With these parameters, we also assume that the uncertainty input from both target and missile maneuvering command, w ˜ (t), the discrete measured noise power, v (kT ) , and initial condition error are satisfied the SIQC in (28) with d = 14000. Also we approximate the flight time Tf = 140 sec. Therefore, with given precision level ε = 1 meter, we can estimate the total quantization noise power during this flight time from (33) as β = 840 .Then we can compute the area of the quantization by following the Theorem 11 as, a = 242.5   and hence, q = 243. Thus for sending six states, e˜(kT ) ∈ R6 , in every sampling period T = 0.1 sec., the CoderDecoder requires bit-rate only 480 bit/sec.

 9LGHRFDPHUDRQO\ 

9LGHRFDPHUDZLWKUDGDU





















     

















7LPH 6HF

Figure 5: Miss distance and angle error in case of ω = 0.1 cos (0.1t)

 9LGHRFDPHUD RQO\



]

7DUJHW

    

9LGHRFDPHUD ZLWKUDGDU

 

 

\



[3] I. R. Manchester and A. V. Savkin, “Circular navigation missile guidance with incomplete information and uncertain autopilot model,” in Proceeding of AIAA Guidance, Navigation, and Control Conference and Exhibit, 2003. [4] I. R. Manchester, A. V. Savkin, and F. A. Faruqi, “Optical-flow based precision missile guidance inspired by honeybee navigation,” in Proceedings of 42nd IEEE Conference on Decision and Control, (Hawaii), Dec. 2003. [5] A. V. Savkin and I. R. Petersen, “Set-valued state estimation via a limited capacity communication channel,” IEEE Trans. on Automatic Control, vol. 48, no. 4, pp. 676–680, 2003.





[2] I. R. Manchester and A. V. Savkin, “Circular navigation guidance law for precision missile target engagements,” in Proceedings of 41st IEEE Conference on Decision and Control, (Las Vegas), pp. 1287–1292, Dec. 2002.

[



[6] V. Malyavej and A. V. Savkin, “Set-valued robust kalman state estimation via digital communication channels with bit-rate constraints,” in Proceedings of American Control Conference, (Denver, Colorado), pp. 1896–1901, Jun. 2003.



Figure 6: Missile and Target trajectory in case of ω = 0.1 cos (0.1t)

7 Conclusion In this paper we have given a constructive method for augmenting measurements from an on-board video camera with data transmitted from a ground-based radar. With more detailed state information available, we can implement a more sophisticated and accurate guidance law. We have shown that significant performance improvements can be made with a data rate as low as 480 bits per second. Furthermore, It is significant that a simple form of Circular Navigation Guidance can be still be implemented with only angle information. Thus if transmissions were to fall out unexpectedly, the guidance law could easily fall back to the simpler case, and still achieve acceptable performance.

References [1] P. N. Pathirana and A. V. Savkin, “Sensor fusion based missile guidance,” in Proceedings of the 6th International Conference on Information Fusion, (Cairns, Australia), pp. 253–260, July. 2003.

[7] A. V. Savkin and I. R. Petersen, “Recursive state estimation for ucertain systems with an integral quadratic constraint,” IEEE Trans. on Automatic Control, vol. 40, no. 6, pp. 1080–1083, 1995. [8] I. R. Petersen and A. V. Savkin, Robust Kalman Filtering for Signals and Systems with Large Uncertainties. Boston: Birkh¨ auser, 1999. [9] B. K. P. Horn, Robot Vision. Massachusetts, Cambridge: The MIT Press, 1986. [10] I. R. Petersen, V. A. Ugrinovski, and A. V. Savkin, Robust Control Design using H ∞ Methods. London: Springer-Verlag, 2000. [11] R. A. Horn and C. R. Johnson, Matrix Analysis. Cambridge, UK: Cambridge University Press, 1985.