Classes | Functions
Tracking Loops
Tracking
Collaboration diagram for Tracking Loops:

Classes

struct  aided_lf_state_t
struct  aided_tl_state_t
struct  comp_tl_state_t
struct  simple_lf_state_t
struct  simple_tl_state_t

Functions

void aided_lf_init (aided_lf_state_t *s, float y0, float pgain, float igain, float aiding_igain)
float aided_lf_update (aided_lf_state_t *s, float p_i_error, float aiding_error)
void aided_tl_init (aided_tl_state_t *s, float loop_freq, float code_freq, float code_bw, float code_zeta, float code_k, float carr_freq, float carr_bw, float carr_zeta, float carr_k, float carr_freq_igain)
void aided_tl_update (aided_tl_state_t *s, correlation_t cs[3])
void calc_loop_gains (float bw, float zeta, float k, float loop_freq, float *pgain, float *igain)
void comp_tl_init (comp_tl_state_t *s, float loop_freq, float code_freq, float code_bw, float code_zeta, float code_k, float carr_freq, float carr_bw, float carr_zeta, float carr_k, float tau, float cpc, u32 sched)
void comp_tl_update (comp_tl_state_t *s, correlation_t cs[3])
float costas_discriminator (float I, float Q)
float dll_discriminator (correlation_t cs[3])
float frequency_discriminator (float I, float Q, float prev_I, float prev_Q)
void simple_lf_init (simple_lf_state_t *s, float y0, float pgain, float igain)
float simple_lf_update (simple_lf_state_t *s, float error)
void simple_tl_init (simple_tl_state_t *s, float loop_freq, float code_freq, float code_bw, float code_zeta, float code_k, float carr_freq, float carr_bw, float carr_zeta, float carr_k)
void simple_tl_update (simple_tl_state_t *s, correlation_t cs[3])

Detailed Description

Functions used by the tracking loops.


Function Documentation

void aided_lf_init ( aided_lf_state_t s,
float  y0,
float  pgain,
float  igain,
float  aiding_igain 
)

Initialize an integral aided loop filter.

This initializes a feedback loop with a PI component, plus an extra independent I term.

Parameters:
sThe loop filter state struct to initialize.
y0The initial value of the output variable, $y_0$.
pgainThe proportional gain of the PI error term, $k_p$.
igainThe integral gain of the PI error term, $k_i$.
aiding_igainThe integral gain of the aiding error term, $k_{ia}$.

Definition at line 225 of file track.c.

float aided_lf_update ( aided_lf_state_t s,
float  p_i_error,
float  aiding_error 
)

Update step for the integral aided loop filter.

This updates a feedback loop with a PI component plus an extra independent I term.

Parameters:
sThe loop filter state struct.
p_i_errorThe error output from the discriminator used in both P and I terms.
aiding_errorThe error output from the discriminator use just in an I term.
Returns:
The updated output variable.

Definition at line 245 of file track.c.

void aided_tl_init ( aided_tl_state_t s,
float  loop_freq,
float  code_freq,
float  code_bw,
float  code_zeta,
float  code_k,
float  carr_freq,
float  carr_bw,
float  carr_zeta,
float  carr_k,
float  carr_freq_igain 
)

Initialise an aided tracking loop.

For a full description of the loop filter parameters, see calc_loop_gains().

TODO, add carrier aiding to the code loop.

Parameters:
sThe tracking loop state struct to initialise.
code_freqThe initial code phase rate (i.e. frequency).
code_bwThe code tracking loop noise bandwidth.
code_zetaThe code tracking loop damping ratio.
code_kThe code tracking loop gain.
carr_freqThe initial carrier frequency.
carr_bwThe carrier tracking loop noise bandwidth.
carr_zetaThe carrier tracking loop damping ratio.
carr_kThe carrier tracking loop gain.

Definition at line 313 of file track.c.

void aided_tl_update ( aided_tl_state_t s,
correlation_t  cs[3] 
)

Update step for the aided tracking loop.

Implements a basic second-order tracking loop. The code tracking loop is a second-order DLL using dll_discriminator() as its discriminator function. The carrier phase tracking loop is a second-order Costas loop using costas_discriminator(), aided by a frequency discriminator using frequency_discriminator().

TODO, add carrier aiding to the code loop.

The tracking loop output variables, i.e. code and carrier frequencies can be read out directly from the state struct.

Parameters:
sThe tracking loop state struct.
csAn array [E, P, L] of correlation_t structs for the Early, Prompt and Late correlations.

Definition at line 350 of file track.c.

void calc_loop_gains ( float  bw,
float  zeta,
float  k,
float  loop_freq,
float *  pgain,
float *  igain 
)

Calculate coefficients for a 2nd order digital PLL / DLL loop filter.

A second order digital PLL consists of a first-order filter and a Numerically Controlled Oscillator (NCO). A linearised model of a digital second order PLL is shown below:

2nd_order_dpll.png
Linearised digital second order PLL model.

Where $K_d$ is the discriminator gain and $F[z]$ and $N[z]$ are the loop filter and NCO transfer functions. The NCO is essentially an accumulator and hence has a transfer function:

\[ N[z] = \frac{K_0 z^{-1}}{1 - z^{-1}} \]

The first-order loop filter is shown below:

1st_order_loop_filter.png
Digital loop filter block diagram.

and has transfer function:

\[ F[z] = \frac{(k_p+k_i) - k_p z^{-1}}{1 - z^{-1}} \]

It is useful to be able to calculate the loop filter coefficients, $k_p$ and $k_i$ by comparison to the parameters used in analog PLL design. By comparison between the digital and analog PLL transfer functions we can show the digital loop filter coefficients are related to the analog PLL natural frequency, $\omega_n$ and damping ratio, $\zeta$ by:

\[ k_p = \frac{1}{k} \frac{8 \zeta \omega_n T} {4 + 4 \zeta \omega_n T + \omega_n^2 T^2} \]

\[ k_i = \frac{1}{k} \frac{4 \omega_n^2 T^2} {4 + 4 \zeta \omega_n T + \omega_n^2 T^2} \]

Where $T$ is the loop update period and the overall loop gain, $k$, is the product of the NCO and discriminator gains, $ k = K_0 K_d $. The natural frequency is related to the loop noise bandwidth, $B_L$ by the following relationship:

\[ \omega_n = \frac{8 \zeta B_L}{4 \zeta^2 + 1} \]

These coefficients are applicable to both the Carrier phase Costas loop and the Code phase DLL.

References:

  1. Performance analysis of an all-digital BPSK direct-sequence spread-spectrum IF receiver architecture. B-Y. Chung, C. Chien, H. Samueli, and R. Jain. IEEE Journal on Selected Areas in Communications, 11:1096–1107, 1993.
Todo:
This math is all wrong, these slides show the analysis we want: http://www.compdsp.com/presentations/Jacobsen/abineau_dpll_analysis.pdf
Parameters:
bwThe loop noise bandwidth, $B_L$.
zetaThe damping ratio, $\zeta$.
kThe loop gain, $k$.
loop_freqThe loop update frequency, $1/T$.
pgainWhere to store the calculated proportional gain, $k_p$.
igainWhere to store the calculated integral gain, $k_i$.

Definition at line 103 of file track.c.

void comp_tl_init ( comp_tl_state_t s,
float  loop_freq,
float  code_freq,
float  code_bw,
float  code_zeta,
float  code_k,
float  carr_freq,
float  carr_bw,
float  carr_zeta,
float  carr_k,
float  tau,
float  cpc,
u32  sched 
)

Initialise a code/carrier phase complimentary filter tracking loop.

For a full description of the loop filter parameters, see calc_loop_gains().

This filter implements gain scheduling. Before `sched` iterations of the loop filter the behaviour will be identical to the simple loop filter. After `sched` iterations, carrier phase information will be used in the code tracking loop.

Note, this filter requires that the code and carrier frequencies are expressed as a difference from the nominal frequncy (e.g. 1.023MHz nominal GPS C/A code phase rate, 4.092MHz IF for the carrier).

Parameters:
sThe tracking loop state struct to initialise.
code_freqThe initial code phase rate (i.e. frequency) difference from nominal.
code_bwThe code tracking loop noise bandwidth.
code_zetaThe code tracking loop damping ratio.
code_kThe code tracking loop gain.
carr_freqThe initial carrier frequency difference from nominal, i.e. Doppler shift.
carr_bwThe carrier tracking loop noise bandwidth.
carr_zetaThe carrier tracking loop damping ratio.
carr_kThe carrier tracking loop gain.
tauThe complimentary filter cross-over frequency.
cpcThe number of carrier cycles per complete code, or equivalently the ratio of the carrier frequency to the nominal code frequency.
schedThe gain scheduling count.

Definition at line 444 of file track.c.

void comp_tl_update ( comp_tl_state_t s,
correlation_t  cs[3] 
)

Update step for a code/carrier phase complimentary filter tracking loop.

The tracking loop output variables, i.e. code and carrier frequencies can be read out directly from the state struct.

Todo:
Write proper documentation with math and diagram.
Parameters:
sThe tracking loop state struct.
csAn array [E, P, L] of correlation_t structs for the Early, Prompt and Late correlations.

Definition at line 480 of file track.c.

float costas_discriminator ( float  I,
float  Q 
)

Phase discriminator for a Costas loop.

costas_loop.png
Costas loop block diagram.

Implements the $\tan^{-1}$ Costas loop discriminator.

\[ \varepsilon_k = \tan^{-1} \left(\frac{I_k}{Q_k}\right) \]

References:

  1. Understanding GPS: Principles and Applications. Elliott D. Kaplan. Artech House, 1996.
Parameters:
IThe prompt in-phase correlation, $I_k$.
QThe prompt quadrature correlation, $Q_k$.
Returns:
The discriminator value, $\varepsilon_k$.

Definition at line 139 of file track.c.

float dll_discriminator ( correlation_t  cs[3])

Normalised non-coherent early-minus-late envelope discriminator.

Implements the normalised non-coherent early-minus-late envelope DLL discriminator.

\[ \varepsilon_k = \frac{1}{2} \frac{E - L}{E + L} \]

where:

\[ E = \sqrt{I^2_E + Q^2_E} \]

\[ L = \sqrt{I^2_L + Q^2_L} \]

References:

  1. Understanding GPS: Principles and Applications. Elliott D. Kaplan. Artech House, 1996.
Parameters:
csAn array [E, P, L] of correlation_t structs for the Early, Prompt and Late correlations.
Returns:
The discriminator value, $\varepsilon_k$.

Definition at line 207 of file track.c.

float frequency_discriminator ( float  I,
float  Q,
float  prev_I,
float  prev_Q 
)

Frequency discriminator for a FLL, used to aid the PLL.

Implements the $atan2$ frequency discriminator.

Strictly speaking this should have a 1 / dt factor, but then we would later multiply the gain by dt again, and it would cancel out. So why do those unnecessary operations at all?

\[ dot_k = abs(I_k * I_{k-1}) + abs(Q_k * Q_{k-1}) cross_k = I_{k-1} * Q_k - I_k * Q_{k-1} \varepsilon_k = atan2 \left(cross_k, dot_k\right) / \pi \]

References:

  1. Understanding GPS: Principles and Applications. Elliott D. Kaplan. Artech House, 1996.
Parameters:
IThe prompt in-phase correlation, $I_k$.
QThe prompt quadrature correlation, $Q_k$.
IThe prompt in-phase correlation, $I_{k-1}$.
QThe prompt quadrature correlation, $Q_{k-1}$.
Returns:
The discriminator value, $\varepsilon_k$.

Definition at line 174 of file track.c.

void simple_lf_init ( simple_lf_state_t s,
float  y0,
float  pgain,
float  igain 
)

Initialise a simple first-order loop filter. The gains can be calculated using calc_loop_gains().

Parameters:
sThe loop filter state struct to initialise.
y0The initial value of the output variable, $y_0$.
pgainThe proportional gain, $k_p$.
igainThe integral gain, $k_i$.

Definition at line 263 of file track.c.

float simple_lf_update ( simple_lf_state_t s,
float  error 
)

Update step for the simple first-order loop filter.

Implements the first-order loop filter as shown below:

1st_order_loop_filter.png
Digital loop filter block diagram.

with transfer function:

\[ F[z] = \frac{(k_p+k_i) - k_p z^{-1}}{1 - z^{-1}} \]

Parameters:
sThe loop filter state struct.
errorThe error output from the discriminator, $\varepsilon_k$.
Returns:
The updated output variable, $y_k$.

Definition at line 288 of file track.c.

void simple_tl_init ( simple_tl_state_t s,
float  loop_freq,
float  code_freq,
float  code_bw,
float  code_zeta,
float  code_k,
float  carr_freq,
float  carr_bw,
float  carr_zeta,
float  carr_k 
)

Initialise a simple tracking loop.

For a full description of the loop filter parameters, see calc_loop_gains().

Parameters:
sThe tracking loop state struct to initialise.
code_freqThe initial code phase rate (i.e. frequency).
code_bwThe code tracking loop noise bandwidth.
code_zetaThe code tracking loop damping ratio.
code_kThe code tracking loop gain.
carr_freqThe initial carrier frequency.
carr_bwThe carrier tracking loop noise bandwidth.
carr_zetaThe carrier tracking loop damping ratio.
carr_kThe carrier tracking loop gain.

Definition at line 376 of file track.c.

Update step for the simple tracking loop.

Implements a basic second-order tracking loop. The code tracking loop is a second-order DLL using dll_discriminator() as its discriminator function. The carrier phase tracking loop is a second-order Costas loop using costas_discriminator().

The tracking loop output variables, i.e. code and carrier frequencies can be read out directly from the state struct.

Parameters:
sThe tracking loop state struct.
csAn array [E, P, L] of correlation_t structs for the Early, Prompt and Late correlations.

Definition at line 407 of file track.c.



swiftnav
Author(s):
autogenerated on Sat Jun 8 2019 18:57:01