-
Notifications
You must be signed in to change notification settings - Fork 13
/
Copy pathcoarse_time_navigation.py
3586 lines (3167 loc) · 163 KB
/
coarse_time_navigation.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# -*- coding: utf-8 -*-
"""Coarse-time navigation and coarse-time Doppler navigation.
Author: Jonas Beuchert
"""
try:
import autograd.numpy as np
except(ImportError):
print("""Package 'autograd' not found. 'autograd.numpy' is necessary for
coarse-time navigation via maximum-likelihood estimation. Falling
back to 'numpy'.""")
import numpy as np
import eph_util as ep
import pymap3d as pm
import itertools as it
import jacobian_height as jh
import scipy.optimize as so
import scipy.stats as ss
from pseudorange_prediction import PseudorangePrediction
from timeout import timeout
import numpy as np2
def coarse_time_doppler_nav(X, d, t, eph, PRN):
"""Coarse-time Doppler navigation.
Works for GPS or Galileo. If using both, concatenate navigation data
(ephemeris) and make sure that satellite indices are unique.
Implemented according to
Fernández-Hernández, I., Borre, K. Snapshot positioning without initial
information. GPS Solutions 20, 605–616 (2016).
https://doi.org/10.1007/s10291-016-0530-4
https://link.springer.com/article/10.1007/s10291-016-0530-4
Inputs:
X - Initial state:
X[0:3] - Receiver position in ECEF XYZ coordinates
X[3] - Receiver clock frequency drift
X[4] - Time difference between initial time and actual time
d - Measured Doppler shifts [Hz]
t - Initial time (coarse time) [s]
eph - ephemeris
PRN - PRNs of visible (acquired) satellites
Outputs:
X - Estimated state
dD - Residuals [m/s]
Author: Jonas Beuchert
"""
fL1 = 1575.42e6 # GPS signal frequency
c = 299792458.0 # Speed of light [m/s]
nIt = 50 # Number of iterations; TODO: Adaptive termination
for k in range(nIt):
# Coarse time + coarse-time error
tow = np.mod(t + X[4], 7*24*60*60) # Time of week [s]
# Identify matching columns in ephemeris matrix, closest column in time
# for each satellite
col = np.array([ep.find_eph(eph, sat, tow) for sat in PRN])
# Extract columns with available data
d = d[~np.isnan(col)]
PRN = PRN[~np.isnan(col)]
col = col[~np.isnan(col)]
eph = eph[:, col]
# Satellite positions, velocities, and accelerations
P, V, A = ep.get_sat_pos_vel_acc(tow, eph)
e = P - X[:3]
e = e / np.linalg.norm(e, axis=1, keepdims=True)
rho = np.linalg.norm(P - X[:3], axis=1, keepdims=True)
# Range rate / satellite-to-receiver relative velocity
rhoDot = np.sum(V * e, axis=1, keepdims=True)
# Satellite-to-reciever relative acceleration
rhoDotDot = np.sum(A * e, axis=1, keepdims=True)
eDot = 1.0 / rho * (V - e * rhoDot)
# Observation matrix
H = np.hstack((eDot, np.ones((d.shape[0], 1)), -rhoDotDot))
Dhat = -np.sum(e * V, axis=1) + X[3] # Predict Doppler [m/s]
D = d * c / fL1 # Doppler measurement [m/s]
dD = D - Dhat # Error
dX = np.linalg.lstsq(H, dD, rcond=None)[0] # Least-squares solution
X = X + dX # Update states
return X, dD
def coarse_time_nav(obs, sats, Eph, TOW_assist_ms, rec_loc_assist, sort=True,
observed_height=None, inter_system_bias=False,
weights=None, hard_constraint=False, tropo='goad',
atm_pressure=1013.0, surf_temp=293.0, humidity=50.0,
iono=None, ion_alpha=np.array([]), ion_beta=np.array([]),
code_period_ms=1):
"""Compute receiver position using coarse-time navigation.
Compute receiver position from fractional pseudoranges using coarse-time
navigation and non-linear least-squares optimisation.
The initial position should be within 100 - 150 km of the true position and
the initial coarse time within about 1 min of the true time.
Works for multiple GNSS, too, e.g., GPS and Galileo. If using more than
one, then concatenate navigation data (ephemerides) and make sure that
satellite indices are unique. E.g., use 1-32 for GPS and 201-250 for
Galileo.
Inputs:
obs - Observations, the fractional pseudo-ranges (sub-millisecond).
sats - SV numbers associated with each observation.
Eph - Table of ephemerides, each column associated with a satellite.
TOW_assist_ms - Coarse time of week [ms], single value or array for
different GNSS times with one value for each satellite.
rec_loc_assist - Initial receiver position in ECEF XYZ coordinates.
sort - Re-sort satellites according to distance [default=True].
observed_height - Height observation [m], default=None
inter_system_bias - Flag indicating if a bias between 2 GNSS is
added as optimisation variable assuming that all
satellites with PRN > 100 belong to the 2nd GNSS
[default=False]
weights - Weight for each observation (height at the end, if present)
[default=None]
hard_constraint - False: Use oberserved_height as additional
observation, i.e., as soft constraint. True: Use
observed_height as hard equality constraint.
[default=False]
tropo - Model for troposheric correction: either None, 'goad' for the
model of C. C. Goad and L. Goodman, 'hopfield' for the model of
H. S. Hopfield, or 'tsui' for the model of J. B.-Y. Tsui
[default='goad']
atm_pressure - Atmospheric pressure at receiver location [mbar] for
troposheric correction, [default=1013.0]
surf_temp - Surface temperature at receiver location [K] for
troposheric corrrection [default=293.0]
humidity - Humidity at receiver location [%] for troposheric correction
[default=50.0]
iono - Model for ionospheric correction: either None or 'klobuchar'
for the model of J. Klobuchar [default=None]
ion_alpha - Alpha parameters for Klobuchar model [default=np.array([])]
ion_beta - Beta parameters for Klobuchar model [default=np.array([])]
code_period_ms - Length of code [ms], either a single value for all
satellites or a numpy array with as many elements as
satellites [default=1]
Outputs:
state - ECEF XYZ position [m,m,m], common bias [m], coarse-time error
[m]; np.NaN if optimization failed
delta_z - Residuals (of pseudoranges) [m]
Author: Jonas Beuchert
"""
def assign_integers(sats, svInxListByDistance, obs, Eph, approx_distances,
code_period_ms=1):
"""Assign Ns according to van Diggelen's algorithm.
Author: Jonas Beuchert
"""
light_ms = 299792458.0 * 0.001
N = np.zeros(sats.shape)
approx_distances = approx_distances / light_ms # Distances in millisec
# Distances from ms to code periods
approx_distances = approx_distances / code_period_ms
unique_code_periods = np.unique(code_period_ms)
n_different_code_periods = len(unique_code_periods)
if not isinstance(code_period_ms, np.ndarray):
N0_inx = svInxListByDistance[0]
else:
N0_inx = np.empty(n_different_code_periods)
for c_idx in np.arange(n_different_code_periods):
N0_inx[c_idx] = svInxListByDistance[
code_period_ms == unique_code_periods[c_idx]
][0]
N0_inx = N0_inx.astype(int)
N[N0_inx] = np.floor(approx_distances[N0_inx])
delta_t = Eph[18, :] * 1000.0 # From sec to millisec
# Time errors from ms to code periods
delta_t = delta_t / code_period_ms
# Observed code phases from ms to code periods
obs = obs / code_period_ms
if not isinstance(code_period_ms, np.ndarray):
for k in svInxListByDistance[1:]:
N[k] = np.round(N[N0_inx] + obs[N0_inx] - obs[k] +
(approx_distances[k] - delta_t[k]) -
(approx_distances[N0_inx] - delta_t[N0_inx]))
else:
for c_idx in np.arange(n_different_code_periods):
curr_svInxListByDistance = svInxListByDistance[
code_period_ms == unique_code_periods[c_idx]
]
for k in curr_svInxListByDistance[1:]:
N[k] = np.round(N[N0_inx[c_idx]] + obs[N0_inx[c_idx]]
- obs[k] +
(approx_distances[k] - delta_t[k]) -
(approx_distances[N0_inx[c_idx]]
- delta_t[N0_inx[c_idx]]))
# Floored distances from code periods to ms
N = N * code_period_ms
return N, N0_inx
# def othieno_assignNs(obs, eph, approx_distances, code_period_ms=1):
# """https://spectrum.library.concordia.ca/973909/1/Othieno_MASc_S2012.pdf"""
# # Approximate time errors
# delta_t = eph[18, :]
# # Speed of light
# c = 299792458.0
# # Predict pseudoranges
# predicted_pr = approx_distances / c / 1e-3 - delta_t / 1e-3
# # Roughly estimate Ns
# N = np.round(predicted_pr - obs)
# # Determine observed / time-free pseudoranges
# observed_pr = N + obs
# # Obtain difference between time-free pseudoranges and predcited ones
# diff = observed_pr - predicted_pr
# # Sort differences in ascending order
# min_idx = np.argmin(np.abs(diff))
# min_diff = diff[min_idx]
# # Compare all differences against 1st one
# diff_2_min = diff - min_diff
# # Adjust pseudoranges that differ by more than half a code period
# threshold = code_period_ms / 2.0
# observed_pr += (diff_2_min < -threshold) * threshold
# observed_pr -= (diff_2_min > threshold) * threshold
# return observed_pr * 1e-3 * c, \
# np.floor(observed_pr) - np.floor(observed_pr[min_idx])
def tx_RAW2tx_GPS(tx_RAW, Eph):
"""Refactoring.
Author: Jonas Beuchert
"""
t0c = Eph[20]
dt = ep.check_t(tx_RAW - t0c)
tcorr = (Eph[1] * dt + Eph[19]) * dt + Eph[18]
tx_GPS = tx_RAW - tcorr
dt = ep.check_t(tx_GPS - t0c)
tcorr = (Eph[1] * dt + Eph[19]) * dt + Eph[18]
tx_GPS = tx_RAW - tcorr
return tx_GPS, tcorr
def e_r_corr(traveltime, X_sat):
"""Rotate satellite by earth rotation during signal travel time.
Author: Jonas Beuchert
"""
Omegae_dot = 7.292115147e-5 # rad/sec
omegatau = Omegae_dot * traveltime
R3 = np.array([np.array([np.cos(omegatau), np.sin(omegatau), 0.0]),
np.array([-np.sin(omegatau), np.cos(omegatau), 0.0]),
np.array([0.0, 0.0, 1.0])])
return R3 @ X_sat
no_iterations = 6
v_light = 299792458.0
dtr = np.pi / 180.0
numSVs = obs.shape[0] # Number of satellites
el = np.zeros(numSVs)
TOW_assist = TOW_assist_ms * 1e-3
if not isinstance(TOW_assist, np.ndarray) or TOW_assist.shape == ():
TOW_assist = TOW_assist * np.ones(sats.shape)
# Identify ephemerides columns in Eph
col_Eph = np.array([ep.find_eph(Eph, sats[k], TOW_assist[k])
for k in range(numSVs)])
Eph = Eph[:, col_Eph] # Sort according to sats argument
# If one common bias shall be used for all systems, then all code phases
# must have same range
if isinstance(code_period_ms, np.ndarray) and not inter_system_bias:
# Greatest common divider of code periods
code_period_ms = np2.gcd.reduce(code_period_ms.astype(int))
obs = np.mod(obs, code_period_ms)
# Number of common-bias optimisation variables
if isinstance(code_period_ms, np.ndarray):
# Assume one entry in code_period_ms for each satellite
# One bias for each present code period
n_bias_opt = np.unique(code_period_ms).shape[0]
elif inter_system_bias:
# Same code period for all systems, nevertheless use inter-system bias
n_bias_opt = 2
else:
# Same code period for all systems, do not use inter-system bias
n_bias_opt = 1
if hard_constraint:
# Transform ECEF XYZ coordinates to geodetic coordinates
latitude, longitude, _ = pm.ecef2geodetic(
rec_loc_assist[0], rec_loc_assist[1], rec_loc_assist[2])
initPosGeo = np.array([latitude, longitude, observed_height])
# Initial receiver postion in EN coordinates
state = np.zeros(2+n_bias_opt+1)
else:
# Preliminary guess for receiver position, common bias, and assistance
# error ([x y z b et] or [x y z b1 b2 et])
state = np.concatenate((rec_loc_assist, np.zeros(n_bias_opt+1)))
T_tilde = TOW_assist
# Find satellite positions at T_tilde
tx_GPS = np.array([TOW_assist[k]
- ep.get_sat_clk_corr(TOW_assist[k],
np.array([sats[k]]),
Eph[:, k, np.newaxis])
for k in range(numSVs)])
satPos_at_T_tilde = np.array([np.squeeze(
ep.get_sat_pos(tx_GPS[k], Eph[:, k, np.newaxis]))
for k in range(numSVs)])
# And then find closest one
approx_distances = np.sqrt(np.sum(
(rec_loc_assist - satPos_at_T_tilde)**2, axis=-1))
if sort:
svInxListByDistance = np.argsort(approx_distances)
else:
svInxListByDistance = np.arange(numSVs)
# if othieno:
# fullPRs, Ks = othieno_assignNs(
# obs, Eph, approx_distances, code_period_ms)
# Ks = Ks * 0
# else:
# Assign N numbers:
Ns, N0_inx = assign_integers(sats, svInxListByDistance, obs, Eph,
approx_distances, code_period_ms)
# Now find K numbers:
if isinstance(code_period_ms, np.ndarray):
unique_code_periods = np.unique(code_period_ms)
n_different_code_periods = len(unique_code_periods)
Ks = np.empty(Ns.shape)
for c_idx in np.arange(n_different_code_periods):
Ks[code_period_ms == unique_code_periods[c_idx]] \
= Ns[code_period_ms == unique_code_periods[c_idx]] \
- Ns[N0_inx[c_idx]]
else:
Ks = Ns - Ns[N0_inx]
fullPRs = Ns + obs # Full pseudoranges reconstruction in ms
fullPRs = fullPRs * (v_light * 1e-3) # In meters
for iter in range(no_iterations):
if hard_constraint:
H = np.empty((numSVs, 3+n_bias_opt))
else:
H = np.empty((numSVs, 4+n_bias_opt))
delta_z = np.empty(numSVs) # Observed minus computed observation
# Coarse-time error
Et = state[-1] # In seconds
for k in svInxListByDistance:
# Common bias [m]
if isinstance(code_period_ms, np.ndarray):
code_period_idx = np.where(
unique_code_periods == code_period_ms[k])[0]
b = state[-1-n_bias_opt+code_period_idx]
elif inter_system_bias and sats[k] > 100:
# Common bias of 2nd GNSS
b = state[-2]
else:
# Common bias of 1st GNSS
b = state[-1-n_bias_opt]
Kk = Ks[k]
tx_GPS, tcorr = tx_RAW2tx_GPS(T_tilde[k] - Et - Kk * 1e-3,
Eph[:, k])
X = ep.get_sat_pos(tx_GPS, Eph[:, k])
X_fut = ep.get_sat_pos(tx_GPS + 1, Eph[:, k])
satECEF = X
sat_futECEF = X_fut
if hard_constraint:
# Transform ECEF XYZ coordinates to ENU coordinates
X[0], X[1], X[2] = pm.ecef2enu(X[0], X[1], X[2], initPosGeo[0],
initPosGeo[1], initPosGeo[2])
X_fut[0], X_fut[1], X_fut[2] = pm.ecef2enu(X_fut[0], X_fut[1],
X_fut[2],
initPosGeo[0],
initPosGeo[1],
initPosGeo[2])
state_memory = state
state = np.array([state[0], state[1], 0.0])
# This if case calculates something about trop
if iter == 0:
traveltime = 0.072
Rot_X = satECEF
Rot_X_fut = sat_futECEF
trop = 0.0
else:
if hard_constraint:
posECEF = np.empty(3)
posECEF[0], posECEF[1], posECEF[2] \
= pm.enu2ecef(state[0], state[1], 0.0,
initPosGeo[0], initPosGeo[1],
initPosGeo[2])
else:
posECEF = state[:3]
rho2 = (satECEF[0] - posECEF[0])**2 \
+ (satECEF[1] - posECEF[1])**2 \
+ (satECEF[2] - posECEF[2])**2 # Distance squared
traveltime = np.sqrt(rho2) / v_light
Rot_X = e_r_corr(traveltime, satECEF)
Rot_X_fut = e_r_corr(traveltime, sat_futECEF)
rho2 = (Rot_X[0] - posECEF[0])**2 \
+ (Rot_X[1] - posECEF[1])**2 \
+ (Rot_X[2] - posECEF[2])**2
if tropo == 'goad':
az, el, dist = ep.topocent(posECEF, Rot_X-posECEF)
trop = ep.tropo(np.sin(el * dtr), 0.0, atm_pressure,
surf_temp, humidity, 0.0, 0.0, 0.0)
elif tropo == 'hopfield':
surf_temp_celsius = surf_temp-273.15
saturation_vapor_pressure = 6.11*10.0**(
7.5*surf_temp_celsius/(237.7+surf_temp_celsius))
vapor_pressure = humidity/100.0 * saturation_vapor_pressure
trop = ep.tropospheric_hopfield(
posECEF, np.array([Rot_X]), surf_temp_celsius,
atm_pressure/10.0, vapor_pressure/10.0)
elif tropo == 'tsui':
lat, lon, h = pm.ecef2geodetic(posECEF[0], posECEF[1],
posECEF[2])
az, el, srange = pm.ecef2aer(Rot_X[0], Rot_X[1], Rot_X[2],
lat, lon, h)
trop = ep.tropospheric_tsui(el)
else:
trop = 0.0
if iono == 'klobuchar':
trop = trop + ep.ionospheric_klobuchar(
posECEF, np.array([Rot_X]),
np.mod(TOW_assist[k], 24*60*60),
ion_alpha, ion_beta) * v_light
elif iono == 'tsui':
lat, lon, h = pm.ecef2geodetic(posECEF[0], posECEF[1],
posECEF[2])
az, el, srange = pm.ecef2aer(Rot_X[0], Rot_X[1], Rot_X[2],
lat, lon, h)
# Convert degrees to semicircles
el = el / 180.0
az = az / 180.0
lat = lat / 180.0
lon = lon / 180.0
# Ionospheric delay [s]
T_iono = ep.ionospheric_tsui(
el, az, lat, lon, TOW_assist[k], ion_alpha, ion_beta)
trop = trop + T_iono * v_light
# Subtraction of state[3] corrects for receiver clock offset and
# v_light*tcorr is the satellite clock offset
predictedPR = np.linalg.norm(Rot_X - state[:3]) + b \
- tcorr * v_light + trop # meters
delta_z[k] = fullPRs[k] - predictedPR # Meters
# Now add row to matrix H according to:
# -e_k 1 v_k
# Notice that it is easier to plug in the location of the satellite
# at its T_dot estimation, i.e., Rot_X
sat_vel_mps = Rot_X_fut - Rot_X
e_k = (Rot_X - (Et + Kk * 1e-3) * sat_vel_mps - state[:3])
e_k = e_k / np.linalg.norm(e_k)
v_k = np.sum(-sat_vel_mps * e_k, keepdims=True) # Relative speed
if hard_constraint:
# Optimise only over E and N coordinate
e_k = e_k[:2]
# Restore state
state = state_memory
if isinstance(code_period_ms, np.ndarray):
code_period_idx = np.where(
unique_code_periods == code_period_ms[k])
jac_common_bias = np.zeros(n_bias_opt)
jac_common_bias[code_period_idx] = 1.0
# Jacobian w.r.t. to common bias of this GNSS
H_row = np.concatenate((-e_k, jac_common_bias,
v_k))
elif not inter_system_bias:
# Matrix for 5 optimisation variables
H_row = np.concatenate((-e_k, np.ones(1), v_k))
else:
# Matrix for 6 optimisation variables
if sats[k] <= 100:
# Jacobian w.r.t. to common bias of 1st GNSS
H_row = np.concatenate((-e_k, np.ones(1), np.zeros(1),
v_k))
else:
# Jacobian w.r.t. to common bias of 2nd GNSS
H_row = np.concatenate((-e_k, np.zeros(1), np.ones(1),
v_k))
# Append Jacobian to end of matrix
H[k] = H_row
# Check if height measurement is provided
if observed_height is not None and not hard_constraint:
# Add Jacobian of height observation
H = np.vstack((H, jh.jacobian_height(state)))
# Predict height based on current state
predicted_height = pm.ecef2geodetic(state[0], state[1], state[2]
)[2]
# Add height measurement
delta_z = np.append(delta_z, observed_height - predicted_height)
if weights is not None:
H = H * np.sqrt(weights[:, np.newaxis])
delta_z = delta_z * np.sqrt(weights)
x = np.linalg.lstsq(H, delta_z, rcond=None)[0]
state = state + x
if hard_constraint:
# Convert ENU to ECEF XYZ coordinates
[pos_x, pos_y, pos_z] = pm.enu2ecef(state[0], state[1], 0.0,
initPosGeo[0], initPosGeo[1],
initPosGeo[2])
state = np.concatenate((np.array([pos_x, pos_y, pos_z]), state[2:]))
return state, delta_z[svInxListByDistance]
def coarse_time_nav_simplified(obs, sats, Eph, TOW_assist_ms, rec_loc_assist, sort=True,
observed_height=None, inter_system_bias=False,
weights=None, hard_constraint=False, tropo='goad',
atm_pressure=1013.0, surf_temp=293.0, humidity=50.0,
iono=None, ion_alpha=np.array([]), ion_beta=np.array([]),
code_period_ms=1, hdop=False, no_iterations=6):
"""Compute receiver position using coarse-time navigation.
Compute receiver position from fractional pseudoranges using coarse-time
navigation and non-linear least-squares optimisation.
The initial position should be within 100 - 150 km of the true position and
the initial coarse time within about 1 min of the true time.
Works for multiple GNSS, too, e.g., GPS and Galileo. If using more than
one, then concatenate navigation data (ephemerides) and make sure that
satellite indices are unique. E.g., use 1-32 for GPS and 201-250 for
Galileo.
Inputs:
obs - Observations, the fractional pseudo-ranges (sub-millisecond).
sats - SV numbers associated with each observation.
Eph - Table of ephemerides, each column associated with a satellite.
TOW_assist_ms - Coarse time of week [ms], single value or array for
different GNSS times with one value for each satellite.
rec_loc_assist - Initial receiver position in ECEF XYZ coordinates.
sort - Obsolete.
observed_height - Height observation [m], default=None
inter_system_bias - Obsolete.
weights - Obsolete.
hard_constraint - Obsolete.
tropo - Obsolete.
atm_pressure - Obsolete.
surf_temp - Obsolete.
humidity - Obsolete.
iono - Obsolete.
ion_alpha - Obsolete.
ion_beta - Obsolete.
code_period_ms - Length of code [ms], either a single value for all
satellites or a numpy array with as many elements as
satellites [default=1]
hdop - Flag if horizontal dilution of precision is returned as 3rd
output, default=False
no_iterations - Number of non-linear least-squares iterations,
default=6
Outputs:
state - ECEF XYZ position [m,m,m], common bias [m], coarse-time error
[m]; np.NaN if optimization failed
delta_z - Residuals (of pseudoranges) [m]
hdop - (Only if hdop=True) Horizontal dilution of precision
Author: Jonas Beuchert
"""
def assign_integers(sats, svInxListByDistance, obs, Eph, approx_distances,
code_period_ms=1):
"""Assign Ns according to van Diggelen's algorithm.
Author: Jonas Beuchert
"""
light_ms = 299792458.0 * 0.001
N = np.zeros(sats.shape)
approx_distances = approx_distances / light_ms # Distances in millisec
# Distances from ms to code periods
approx_distances = approx_distances / code_period_ms
# To integer
N[0] = np.floor(approx_distances[0])
delta_t = Eph[18, :] * 1000.0 # From sec to millisec
# Time errors from ms to code periods
delta_t = delta_t / code_period_ms
# Observed code phases from ms to code periods
obs = obs / code_period_ms
N[1:] = np.round(N[0] + obs[0] - obs[1:] +
(approx_distances[1:] - delta_t[1:]) -
(approx_distances[0] - delta_t[0]))
# Floored distances from code periods to ms
N = N * code_period_ms
return N
def tx_RAW2tx_GPS(tx_RAW, Eph):
"""Refactoring.
Author: Jonas Beuchert
"""
t0c = Eph[20]
dt = ep.check_t_vectorized(tx_RAW - t0c)
tcorr = (Eph[1] * dt + Eph[19]) * dt + Eph[18]
tx_GPS = tx_RAW - tcorr
dt = ep.check_t_vectorized(tx_GPS - t0c)
tcorr = (Eph[1] * dt + Eph[19]) * dt + Eph[18]
tx_GPS = tx_RAW - tcorr
return tx_GPS, tcorr
def e_r_corr(traveltime, sat_pos, n_sats):
"""Rotate satellite by earth rotation during signal travel time.
Author: Jonas Beuchert
"""
Omegae_dot = 7.292115147e-5 # rad/sec
omegatau = Omegae_dot * traveltime
# Vector of rotation matrices
R3 = np.transpose(np.array([
np.array([np.cos(omegatau), np.sin(omegatau), np.zeros(n_sats)]),
np.array([-np.sin(omegatau), np.cos(omegatau), np.zeros(n_sats)]),
np.array([np.zeros(n_sats), np.zeros(n_sats), np.ones(n_sats)])]),
axes=(2, 0, 1))
# Turn satellite positions into vector of column vectors
sat_pos = np.array([sat_pos]).transpose(1, 2, 0)
return np.matmul(R3, sat_pos).reshape(n_sats, 3)
v_light = 299792458.0
numSVs = obs.shape[0] # Number of satellites
TOW_assist = TOW_assist_ms * 1e-3
if not isinstance(TOW_assist, np.ndarray) or TOW_assist.shape == ():
TOW_assist = TOW_assist * np.ones(sats.shape)
if Eph.shape[1] != sats.shape[0] or np.any(Eph[0] != sats):
# Identify ephemerides columns in Eph
col_Eph = np.array([ep.find_eph(Eph, sats[k], TOW_assist[k])
for k in range(numSVs)])
Eph = Eph[:, col_Eph] # Sort according to sats argument
# If one common bias shall be used for all systems, then all code phases
# must have same range
if isinstance(code_period_ms, np.ndarray):
# Greatest common divider of code periods
code_period_ms = np2.gcd.reduce(code_period_ms.astype(int))
obs = np.mod(obs, code_period_ms)
# Number of common-bias optimisation variables
# Same code period for all systems, do not use inter-system bias
n_bias_opt = 1
# Preliminary guess for receiver position, common bias, and assistance
# error ([x y z b et] or [x y z b1 b2 et])
state = np.concatenate((rec_loc_assist, np.zeros(n_bias_opt+1)))
T_tilde = TOW_assist
# Find satellite positions at T_tilde
tx_GPS = TOW_assist - ep.get_sat_clk_corr_vectorized(TOW_assist, sats, Eph)
satPos_at_T_tilde = ep.get_sat_pos(tx_GPS, Eph)
# And then find closest one
approx_distances = np.sqrt(np.sum(
(rec_loc_assist - satPos_at_T_tilde)**2, axis=-1))
sat_idx = np.arange(numSVs)
# Assign N numbers:
Ns = assign_integers(sats, sat_idx, obs, Eph,
approx_distances, code_period_ms)
Ks = Ns - Ns[0]
fullPRs = Ns + obs # Full pseudoranges reconstruction in ms
fullPRs = fullPRs * (v_light * 1e-3) # In meters
# Intialization
H = np.empty((numSVs, 4+n_bias_opt)) # Linear system matrix
delta_z = np.empty(numSVs) # Observed minus computed observation
for iteration_idx in np.arange(no_iterations):
# Coarse-time error
Et = state[-1] # In seconds
# Common bias [m]
b = state[-1-n_bias_opt]
tx_GPS, tcorr = tx_RAW2tx_GPS(T_tilde - Et - Ks * 1e-3, Eph)
sat_pos, sat_vel = ep.get_sat_pos_vel(tx_GPS, Eph)
if iteration_idx == 0:
traveltime = 0.072
rot_sat_pos = sat_pos
else:
posECEF = state[:3]
rho2 = (sat_pos[:, 0] - posECEF[0])**2 \
+ (sat_pos[:, 1] - posECEF[1])**2 \
+ (sat_pos[:, 2] - posECEF[2])**2 # Distance squared
traveltime = np.sqrt(rho2) / v_light
rot_sat_pos = e_r_corr(traveltime, sat_pos, numSVs)
# Subtraction of state[3] corrects for receiver clock offset and
# v_light*tcorr is the satellite clock offset
predictedPR = np.linalg.norm(rot_sat_pos - state[:3], axis=-1) \
+ b - tcorr * v_light # meters
delta_z = fullPRs - predictedPR # Meters
# Receiver-satellite vector
e_k = (rot_sat_pos
- np.tile(np.array([Et + Ks * 1e-3]).T, (1, 3)) * sat_vel
- state[:3])
# Normalize receiver-satellite vector
e_k = e_k / np.array([np.linalg.norm(e_k, axis=-1)]).T
# Relative satellite velocity along this vector, i.e.,
# project satellite velocity on normalized receiver-satellite vector
v_k = np.sum(-sat_vel * e_k, axis=1, keepdims=True)
# Now build Jacobian matrix H according to:
# -e_k 1 v_k
# Notice that it is easier to plug in the location of the satellite
# at its T_dot estimation, i.e., rot_sat_pos
# Matrix for 5 optimisation variables
H = np.hstack((-e_k, np.ones((numSVs, 1)), v_k))
# Check if height measurement is provided
if observed_height is not None:
# Add Jacobian of height observation
H = np.vstack((H, jh.jacobian_height(state)))
# Predict height based on current state
predicted_height = pm.ecef2geodetic(state[0], state[1], state[2]
)[2]
# Add height measurement
delta_z = np.append(delta_z, observed_height - predicted_height)
x = np.linalg.lstsq(H, delta_z, rcond=None)[0]
state = state + x
if hdop:
try:
Q = np.linalg.inv(H.T @ H)
dilution_east_squared = Q[0, 0]
dilution_north_squared = Q[1, 1]
hdop = np.sqrt(dilution_east_squared + dilution_north_squared)
return state, delta_z, hdop
except:
print("Cannot calculate HDOP.")
return state, delta_z, np.nan
return state, delta_z
def cold_snapshot(c, d, t_min, t_max, eph, PRN, init_pos=np.zeros(3)):
"""Cold snapshot algorithm.
Coarse-time Doppler navigation combined with coarse-time navigation.
Works for GPS or Galileo with code-phases in the intervall 0 - 1 ms. If
using both, concatenate navigation data (ephemeris) and make sure that
satellite indices are unique.
Inputs:
c - Measured code phases [ms]
d - Measured Doppler shifts [Hz]
t_min - Start of time interval (datetime or GPS time [s])
t_max - End of time interval (datetime or GPS time [s])
eph - ephemeris
PRN - PRNs of visible (acquired) satellites
init_pos - [Optional] initial psoition in ECEF XYZ coordinates [m,m,m]
Outputs:
X_opt - Estimated state
res_opt - Pseudorange residuals [m]
t_opt - Estimated coarse time (GPS time) [s]; subtract X_opt[4] for more
precise time estimate; X_opt[4] is the coarse time error
Implemented according to
Fernández-Hernández, I., Borre, K. Snapshot positioning without initial
information. GPS Solut 20, 605–616 (2016)
https://doi.org/10.1007/s10291-016-0530-4
https://link.springer.com/article/10.1007/s10291-016-0530-4
Author: Jonas Beuchert
"""
dt = 3.0 * 60.0 * 60.0 # Step size for iterations [s]
if isinstance(t_min, np.datetime64):
t_min = ep.utc_2_gps_time(t_min)
if isinstance(t_max, np.datetime64):
t_max = ep.utc_2_gps_time(t_max)
T = np.arange(t_min, t_max, dt) # Coarse time grid
if T[-1] < t_max:
np.append(T, t_max)
X0 = np.zeros(5) # Initialize
X0[:3] = init_pos # Set initial position
dDmin = np.inf
# Intialize outputs
Xopt = X0
resOpt = np.full(5, np.inf)
tOpt = np.mean(np.array([t_min, t_max]))
for t in T: # Calculate one solution every 3 h
X, dD = coarse_time_doppler_nav(X0, d, t, eph, PRN)
# Convert code phases from s to ms
code_phases = c / 1e-3
# Time of week in ms incl. correction from coarse time Doppler nav.
initTimeMs = np.mod(t + X[4], 7 * 24 * 60 * 60) / 1e-3
# Get initial position from coarse time Doppler navigation
init_pos = X[:3]
# Coarse-time navigation
lsEstimate, resPseudoranges = coarse_time_nav(code_phases, PRN, eph,
initTimeMs, init_pos)
# If norm of pseudorange residuals is smaller than current optimum
if np.linalg.norm(resPseudoranges) < dDmin:
# Set new optimum
dDmin = np.linalg.norm(resPseudoranges)
# Store state as best solution
Xopt = lsEstimate
# Store residuals as smallest residuals
resOpt = resPseudoranges
# Store coarse time
tOpt = t + X[4]
return Xopt, resOpt, tOpt
def warm_start_acquisition(data, interm_freq, sampling_freq, init_pos,
init_bias, init_time, eph, ms_to_process=1,
elev_mask=10, pos_err_max=1.414248917270224e+04,
bias_err_max=1.5e4, time_err_max=1, gnss='gps',
ref=True, corr=False):
"""Warm-started acquisition and code phase estimation.
Perform acquisition and keep only satellites whose code phase estimates
are close to the predicted values based on an initial position, common
bias, and time.
Inputs:
data - GNSS snapshot
interm_freq - Intermediate frequency [Hz]
sampling_freq - Sampling freqeuncy [Hz]
init_pos - Initial receiver position in ECEF XYZ [m,m,m]
init_bias - Initial common pseudorange bias [m]
init_time - Initial coarse time [s]
eph - Ephemeris matrix
ms_to_process - Number of milliseconds of the snapshot to use
elev_mask - Elevation mask for predicting satellites [deg]
pos_err_max - Maximum expected horizontal receiver position error
w.r.t. initial position [m]
bias_err_max - Maximum expected common bias deviation w.r.t. initial
bias [m]
time_err_max - Maximum expected receiver clock deviation w.r.t. initial
coarse time [s]
gnss - Type of GNSS, 'gps' or 'galileo', default='gps'
ref - Switch for type of code-phase prediction, True for algorithm
according to van Diggelen based on one reference satellite, False
for algorithm according to Bissig et al. with two iterations for
each satellite independently, default=True
corr - Switch for atmospheric correction when prediciting code phases,
default=False
Outputs:
PRN - Indices of satellites whose estimated code phases are close to
the predicted values
code_phases - Estimated code phases that are close to the predicted
values [ms]
peak_metrics - Estimated signal-to-noise ratios (SNR) of satellites
whose estimated code phases are close to the predicted
values [dB]
code_phase_err - Absolute differences between estimated and predicted
code phases of returned satellites [ms]
Author: Jonas Beuchert
"""
if gnss == 'gps':
code_duration = 1e-3
elif gnss == 'galileo':
code_duration = 4e-3
else:
raise ValueError(
"Chosen GNSS not supported, select 'gps' or 'galileo'.")
# Maximum expected satellite speed relative to receiver [m/s]
sat_vel_max = 14.0e3 / 60.0 / 60.0
# Speed of light [m/s]
c = 299792458.0
# Convert initial position from Cartesian to geodetic coordinates
init_pos_geo = np.empty(3)
init_pos_geo[0], init_pos_geo[1], init_pos_geo[2] = pm.ecef2geodetic(
init_pos[0], init_pos[1], init_pos[2])
# Predict set of visible satellites
acq_satellite_list = ep.get_visible_sats(init_time, init_pos_geo, eph,
elev_mask)
# Calculate maximum code phase estimation error [ms]
code_phase_err_max = (time_err_max * sat_vel_max + pos_err_max
+ bias_err_max) / c / 1e-3
if ref:
# Predict pseudoranges
pr = ep.predict_pseudoranges(acq_satellite_list, eph, init_time,
init_pos, init_bias, corr)
# Convert predicted pseudoranges to code phases in milliseconds
init_code_phases = np.mod(pr / c, code_duration) / 1e-3
else:
# Predict code phases
init_code_phases = ep.get_code_phase(init_time, init_pos, init_bias,
acq_satellite_list, eph,
code_duration, corr) / 1e-3
# Estimate code phases
acquired_sv, acquired_snr, acquired_doppler, acquired_codedelay,\
acquired_fine_freq, results_doppler, results_code_phase,\
results_peak_metric = ep.acquisition(data, interm_freq, sampling_freq,
ms_to_process=ms_to_process,
prn_list=acq_satellite_list,
fine_freq=False, gnss=gnss)
# Convert code phases from number of samples to ms
code_phases = results_code_phase[acq_satellite_list - 1] / sampling_freq \
/ 1e-3
# Calculate difference between extimated and observed code phases
code_phase_err = np.abs(code_phases - init_code_phases)
code_phase_err = np.min(np.array([code_phase_err, 1.0 - code_phase_err]),
axis=0)
# Keep only satellites where difference is small
PRN = acq_satellite_list[code_phase_err < code_phase_err_max]
code_phases = results_code_phase[PRN - 1] / sampling_freq / 1e-3
peak_metrics = results_peak_metric[PRN - 1]
code_phase_err = code_phase_err[code_phase_err < code_phase_err_max]
return PRN, code_phases, peak_metrics, code_phase_err
def selective_coarse_time_nav(PRN, code_phases, peak_metrics, eph, init_pos,
init_time, init_height=0, height_err_max=200,
sort_key='elevation', code_phase_err=None,
mode='SNR', return_prn=False,
observed_height=None, inter_system_bias=False,
weights=None, hard_constraint=False,
tropo='goad', atm_pressure=1013.0,
surf_temp=293.0, humidity=50.0, iono='none',
ion_alpha=np.array([]), ion_beta=np.array([]),
code_period_ms=1,
max_dist=None, max_time=None,
max_residual=100):
"""Coarse-time navigation (CTN) with iterative solution checking.
Coarse-time navigation (CTN) with iterative solution checking and
discarding of unreliable satellites.
The initial position should be within 100 - 150 km of the true position and
the initial coarse time within about 1 min of the true time.
Inputs:
PRN - Indices of acquired satellites
code_phases - Code phases of acquired satellites [ms], 0-1
peak_metrics - Realiability metrics for acquired satellites, e.g.,
signal-to-noise ratios (SNR)
init_pos - Initial receiver position in ECEF XYZ [m,m,m]
init_time - Initial coarse time [s], single value or array for
different GNSS times with one value for each satellite
eph - Ephemeris matrix
init_height - Expected height above sea level (WGS84) [m], default=0,
None to disable height check