View Javadoc
1   /*
2    * Copyright (C) 2019 Alberto Irurueta Carro (alberto@irurueta.com)
3    *
4    * Licensed under the Apache License, Version 2.0 (the "License");
5    * you may not use this file except in compliance with the License.
6    * You may obtain a copy of the License at
7    *
8    *         http://www.apache.org/licenses/LICENSE-2.0
9    *
10   * Unless required by applicable law or agreed to in writing, software
11   * distributed under the License is distributed on an "AS IS" BASIS,
12   * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13   * See the License for the specific language governing permissions and
14   * limitations under the License.
15   */
16  package com.irurueta.navigation.gnss;
17  
18  import com.irurueta.units.Distance;
19  import com.irurueta.units.DistanceConverter;
20  import com.irurueta.units.DistanceUnit;
21  import com.irurueta.units.Speed;
22  import com.irurueta.units.SpeedConverter;
23  import com.irurueta.units.SpeedUnit;
24  
25  import java.io.Serializable;
26  import java.util.Objects;
27  
28  /**
29   * Contains GNSS Kalman filter configuration parameters (usually obtained through calibration) to
30   * determine the system noise covariance matrix.
31   */
32  public class GNSSKalmanConfig implements Serializable, Cloneable {
33  
34      /**
35       * Initial position uncertainty per axis expressed in meters (m).
36       */
37      private double initialPositionUncertainty;
38  
39      /**
40       * Initial velocity uncertainty per axis expressed in meters per second (m/s).
41       */
42      private double initialVelocityUncertainty;
43  
44      /**
45       * Initial clock offset uncertainty per axis expressed in meters (m).
46       */
47      private double initialClockOffsetUncertainty;
48  
49      /**
50       * Initial clock drift uncertainty per axis expressed in meters per second (m/s).
51       */
52      private double initialClockDriftUncertainty;
53  
54      /**
55       * Acceleration PSD (Power Spectral Density) per axis expressed in (m^2/s^3).
56       */
57      private double accelerationPSD;
58  
59      /**
60       * Receiver clock frequency-drift PSD (Power Spectral Density) expressed in
61       * (m^2/s^3).
62       */
63      private double clockFrequencyPSD;
64  
65      /**
66       * Receiver clock phase-drift PSD (Power Spectral Density) expressed in (m^2/s).
67       */
68      private double clockPhasePSD;
69  
70      /**
71       * Pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
72       */
73      private double pseudoRangeSD;
74  
75      /**
76       * Pseudo-range rate measurement noise SD (Standard Deviation) expressed in meters
77       * per second (m/s).
78       */
79      private double rangeRateSD;
80  
81      /**
82       * Constructor.
83       */
84      public GNSSKalmanConfig() {
85      }
86  
87      /**
88       * Constructor.
89       *
90       * @param initialPositionUncertainty    initial position uncertainty per axis expressed in
91       *                                      meters (m).
92       * @param initialVelocityUncertainty    initial velocity uncertainty per axis expressed in
93       *                                      meters per second (m/s).
94       * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis expressed in
95       *                                      meters (m).
96       * @param initialClockDriftUncertainty  initial clock drift uncertainty per axis expressed in
97       *                                      meters per second (m/s).
98       * @param accelerationPSD               acceleration PSD (Power Spectral Density) per axis
99       *                                      expressed in (m^2/s^3).
100      * @param clockFrequencyPSD             receiver clock frequency-drift PSD (Power Spectral
101      *                                      Density) expressed in (m^2/s^3).
102      * @param clockPhasePSD                 receiver clock phase-drift PSD (Power Spectral Density)
103      *                                      expressed in (m^2/s).
104      * @param pseudoRangeSD                 pseudo-range measurement noise SD (Standard Deviation)
105      *                                      expressed in meters (m).
106      * @param rangeRateSD                   pseudo-range measurement noise SD (Standard Deviation)
107      *                                      expressed in meters per second (m/s).
108      */
109     public GNSSKalmanConfig(final double initialPositionUncertainty,
110                             final double initialVelocityUncertainty,
111                             final double initialClockOffsetUncertainty,
112                             final double initialClockDriftUncertainty,
113                             final double accelerationPSD, final double clockFrequencyPSD,
114                             final double clockPhasePSD, final double pseudoRangeSD,
115                             final double rangeRateSD) {
116         setValues(initialPositionUncertainty, initialVelocityUncertainty, initialClockOffsetUncertainty,
117                 initialClockDriftUncertainty, accelerationPSD, clockFrequencyPSD, clockPhasePSD, pseudoRangeSD,
118                 rangeRateSD);
119     }
120 
121     /**
122      * Constructor.
123      *
124      * @param initialPositionUncertainty    initial position uncertainty per axis.
125      * @param initialVelocityUncertainty    initial velocity uncertainty per axis.
126      * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis.
127      * @param initialClockDriftUncertainty  initial clock drift uncertainty per axis.
128      * @param accelerationPSD               acceleration PSD (Power Spectral Density) per axis
129      *                                      expressed in (m^2/s^3).
130      * @param clockFrequencyPSD             receiver clock frequency-drift PSD (Power Spectral
131      *                                      Density) expressed in (m^2/s^3).
132      * @param clockPhasePSD                 receiver clock phase-drift PSD (Power Spectral Density)
133      *                                      expressed in (m^2/s).
134      * @param pseudoRangeSD                 pseudo-range measurement noise SD (Standard Deviation)
135      *                                      expressed in meters (m).
136      * @param rangeRateSD                   pseudo-range measurement noise SD (Standard Deviation)
137      *                                      expressed in meters per second (m/s).
138      */
139     public GNSSKalmanConfig(final Distance initialPositionUncertainty,
140                             final Speed initialVelocityUncertainty,
141                             final Distance initialClockOffsetUncertainty,
142                             final Speed initialClockDriftUncertainty,
143                             final double accelerationPSD, final double clockFrequencyPSD,
144                             final double clockPhasePSD, final Distance pseudoRangeSD,
145                             final Speed rangeRateSD) {
146         setValues(initialPositionUncertainty, initialVelocityUncertainty, initialClockOffsetUncertainty,
147                 initialClockDriftUncertainty, accelerationPSD, clockFrequencyPSD, clockPhasePSD, pseudoRangeSD,
148                 rangeRateSD);
149     }
150 
151     /**
152      * Copy constructor.
153      *
154      * @param input input instance to copy data from.
155      */
156     public GNSSKalmanConfig(final GNSSKalmanConfig input) {
157         copyFrom(input);
158     }
159 
160     /**
161      * Gets initial position uncertainty per axis expressed in meters (m).
162      *
163      * @return initial position uncertainty per axis.
164      */
165     public double getInitialPositionUncertainty() {
166         return initialPositionUncertainty;
167     }
168 
169     /**
170      * Sets initial position uncertainty per axis expressed in meters (m).
171      *
172      * @param initialPositionUncertainty initial position uncertainty per axis.
173      */
174     public void setInitialPositionUncertainty(final double initialPositionUncertainty) {
175         this.initialPositionUncertainty = initialPositionUncertainty;
176     }
177 
178     /**
179      * Gets initial position uncertainty per axis.
180      *
181      * @param result instance where initial position uncertainty per axis will be stored.
182      */
183     public void getDistanceInitialPositionUncertainty(final Distance result) {
184         result.setValue(initialPositionUncertainty);
185         result.setUnit(DistanceUnit.METER);
186     }
187 
188     /**
189      * Gets initial position uncertainty per axis.
190      *
191      * @return initial position uncertainty per axis.
192      */
193     public Distance getDistanceInitialPositionUncertainty() {
194         return new Distance(initialPositionUncertainty, DistanceUnit.METER);
195     }
196 
197     /**
198      * Sets initial position uncertainty per axis.
199      *
200      * @param initialPositionUncertainty initial position uncertainty per axis.
201      */
202     public void setInitialPositionUncertainty(final Distance initialPositionUncertainty) {
203         this.initialPositionUncertainty = DistanceConverter.convert(
204                 initialPositionUncertainty.getValue().doubleValue(), initialPositionUncertainty.getUnit(),
205                 DistanceUnit.METER);
206     }
207 
208     /**
209      * Gets initial velocity uncertainty per axis expressed in meters per second (m/s).
210      *
211      * @return initial velocity uncertainty per axis.
212      */
213     public double getInitialVelocityUncertainty() {
214         return initialVelocityUncertainty;
215     }
216 
217     /**
218      * Sets initial velocity uncertainty per axis expressed in meters per second (m/s).
219      *
220      * @param initialVelocityUncertainty initial velocity uncertainty per axis.
221      */
222     public void setInitialVelocityUncertainty(final double initialVelocityUncertainty) {
223         this.initialVelocityUncertainty = initialVelocityUncertainty;
224     }
225 
226     /**
227      * Gets initial velocity uncertainty per axis.
228      *
229      * @param result instance where initial velocity uncertainty per axis will be stored.
230      */
231     public void getSpeedInitialVelocityUncertainty(final Speed result) {
232         result.setValue(initialVelocityUncertainty);
233         result.setUnit(SpeedUnit.METERS_PER_SECOND);
234     }
235 
236     /**
237      * Gets initial velocity uncertainty per axis.
238      *
239      * @return initial velocity uncertainty per axis.
240      */
241     public Speed getSpeedInitialVelocityUncertainty() {
242         return new Speed(initialVelocityUncertainty, SpeedUnit.METERS_PER_SECOND);
243     }
244 
245     /**
246      * Sets initial velocity uncertainty per axis.
247      *
248      * @param initialVelocityUncertainty initial velocity uncertainty per axis.
249      */
250     public void setInitialVelocityUncertainty(final Speed initialVelocityUncertainty) {
251         this.initialVelocityUncertainty = SpeedConverter.convert(initialVelocityUncertainty.getValue().doubleValue(),
252                 initialVelocityUncertainty.getUnit(), SpeedUnit.METERS_PER_SECOND);
253     }
254 
255     /**
256      * Gets initial clock offset uncertainty per axis expressed in meters (m).
257      *
258      * @return initial clock offset uncertainty per axis.
259      */
260     public double getInitialClockOffsetUncertainty() {
261         return initialClockOffsetUncertainty;
262     }
263 
264     /**
265      * Sets initial clock offset uncertainty per axis expressed in meters (m).
266      *
267      * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis.
268      */
269     public void setInitialClockOffsetUncertainty(final double initialClockOffsetUncertainty) {
270         this.initialClockOffsetUncertainty = initialClockOffsetUncertainty;
271     }
272 
273     /**
274      * Gets initial clock offset uncertainty per axis.
275      *
276      * @param result instance where initial clock offset uncertainty per axis will be stored.
277      */
278     public void getDistanceInitialClockOffsetUncertainty(final Distance result) {
279         result.setValue(initialClockOffsetUncertainty);
280         result.setUnit(DistanceUnit.METER);
281     }
282 
283     /**
284      * Gets initial clock offset uncertainty per axis.
285      *
286      * @return initial clock offset uncertainty per axis.
287      */
288     public Distance getDistanceInitialClockOffsetUncertainty() {
289         return new Distance(initialClockOffsetUncertainty, DistanceUnit.METER);
290     }
291 
292     /**
293      * Sets initial clock offset uncertainty per axis.
294      *
295      * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis.
296      */
297     public void setInitialClockOffsetUncertainty(final Distance initialClockOffsetUncertainty) {
298         this.initialClockOffsetUncertainty = DistanceConverter.convert(
299                 initialClockOffsetUncertainty.getValue().doubleValue(), initialClockOffsetUncertainty.getUnit(),
300                 DistanceUnit.METER);
301     }
302 
303     /**
304      * Gets initial clock drift uncertainty per axis expressed in meters per second (m/s).
305      *
306      * @return initial clock drift uncertainty per axis.
307      */
308     public double getInitialClockDriftUncertainty() {
309         return initialClockDriftUncertainty;
310     }
311 
312     /**
313      * Sets initial clock drift uncertainty per axis expressed in meters per second (m/s).
314      *
315      * @param initialClockDriftUncertainty initial clock drift uncertainty per axis.
316      */
317     public void setInitialClockDriftUncertainty(final double initialClockDriftUncertainty) {
318         this.initialClockDriftUncertainty = initialClockDriftUncertainty;
319     }
320 
321     /**
322      * Gets initial clock drift uncertainty per axis.
323      *
324      * @param result instance where initial clock drift uncertainty per axis will be stored.
325      */
326     public void getSpeedInitialClockDriftUncertainty(final Speed result) {
327         result.setValue(initialClockDriftUncertainty);
328         result.setUnit(SpeedUnit.METERS_PER_SECOND);
329     }
330 
331     /**
332      * Gets initial clock drift uncertainty per axis.
333      *
334      * @return initial clock drift uncertainty per axis.
335      */
336     public Speed getSpeedInitialClockDriftUncertainty() {
337         return new Speed(initialClockDriftUncertainty, SpeedUnit.METERS_PER_SECOND);
338     }
339 
340     /**
341      * Sets initial clock drift uncertainty per axis.
342      *
343      * @param initialClockDriftUncertainty initial clock drift uncertainty per axis.
344      */
345     public void setInitialClockDriftUncertainty(final Speed initialClockDriftUncertainty) {
346         this.initialClockDriftUncertainty = SpeedConverter.convert(
347                 initialClockDriftUncertainty.getValue().doubleValue(), initialClockDriftUncertainty.getUnit(),
348                 SpeedUnit.METERS_PER_SECOND);
349     }
350 
351     /**
352      * Gets acceleration PSD (Power Spectral Density) per axis expressed in (m^2/s^3).
353      *
354      * @return acceleration PSD.
355      */
356     public double getAccelerationPSD() {
357         return accelerationPSD;
358     }
359 
360     /**
361      * Sets acceleration PSD (Power Spectral Density) per axis expressed in (m^2/s^3).
362      *
363      * @param accelerationPSD acceleration PSD.
364      */
365     public void setAccelerationPSD(final double accelerationPSD) {
366         this.accelerationPSD = accelerationPSD;
367     }
368 
369     /**
370      * Gets receiver clock frequency-drift PSD (Power Spectral Density) expressed in
371      * (m^2/s^3).
372      *
373      * @return receiver clock frequency-drift PSD.
374      */
375     public double getClockFrequencyPSD() {
376         return clockFrequencyPSD;
377     }
378 
379     /**
380      * Sets receiver clock frequency-drift PSD (Power Spectral Density) expressed in
381      * (m^2/s^3).
382      *
383      * @param clockFrequencyPSD receiver clock frequency-drift PSD.
384      */
385     public void setClockFrequencyPSD(final double clockFrequencyPSD) {
386         this.clockFrequencyPSD = clockFrequencyPSD;
387     }
388 
389     /**
390      * Gets receiver clock phase-drift PSD (Power Spectral Density) expressed in
391      * (m^2/s).
392      *
393      * @return receiver clock phase-drift PSD.
394      */
395     public double getClockPhasePSD() {
396         return clockPhasePSD;
397     }
398 
399     /**
400      * Sets receiver clock phase-drift PSD (Power Spectral Density) expressed in
401      * (m^2/s).
402      *
403      * @param clockPhasePSD receiver clock phase-drift PSD.
404      */
405     public void setClockPhasePSD(final double clockPhasePSD) {
406         this.clockPhasePSD = clockPhasePSD;
407     }
408 
409     /**
410      * Gets pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
411      *
412      * @return pseudo-range measurement noise SD.
413      */
414     public double getPseudoRangeSD() {
415         return pseudoRangeSD;
416     }
417 
418     /**
419      * Sets pseudo-range measurement noise SD (Standard Deviation) expressed in meters (m).
420      *
421      * @param pseudoRangeSD pseudo-range measurement noise SD.
422      */
423     public void setPseudoRangeSD(final double pseudoRangeSD) {
424         this.pseudoRangeSD = pseudoRangeSD;
425     }
426 
427     /**
428      * Gets pseudo-range measurement noise SD (Standard Deviation).
429      *
430      * @param result instance where pseudo-range measurement noise SD will be stored.
431      */
432     public void getDistancePseudoRangeSD(final Distance result) {
433         result.setValue(pseudoRangeSD);
434         result.setUnit(DistanceUnit.METER);
435     }
436 
437     /**
438      * Gets pseudo-range measurement noise SD (Standard Deviation).
439      *
440      * @return pseudo-range measurement noise SD.
441      */
442     public Distance getDistancePseudoRangeSD() {
443         return new Distance(pseudoRangeSD, DistanceUnit.METER);
444     }
445 
446     /**
447      * Sets pseudo-range measurement noise SD (Standard Deviation).
448      *
449      * @param pseudoRangeSD pseudo-range measurement noise SD.
450      */
451     public void setPseudoRangeSD(final Distance pseudoRangeSD) {
452         this.pseudoRangeSD = DistanceConverter.convert(pseudoRangeSD.getValue().doubleValue(), pseudoRangeSD.getUnit(),
453                 DistanceUnit.METER);
454     }
455 
456     /**
457      * Gets pseudo-range rate measurement SD (Standard Deviation) expressed in meters
458      * per second (m/s).
459      *
460      * @return pseudo-range rate measurement SD.
461      */
462     public double getRangeRateSD() {
463         return rangeRateSD;
464     }
465 
466     /**
467      * Sets pseudo-range rate measurement SD (Standard Deviation) expressed in meters
468      * per second (m/s).
469      *
470      * @param rangeRateSD pseudo-range rate measurement SD.
471      */
472     public void setRangeRateSD(final double rangeRateSD) {
473         this.rangeRateSD = rangeRateSD;
474     }
475 
476     /**
477      * Gets pseudo-range rate measurement noise SD (Standard Deviation).
478      *
479      * @param result instance where pseudo-range rate measurement noise SD will be
480      *               stored.
481      */
482     public void getSpeedRangeRateSD(final Speed result) {
483         result.setValue(rangeRateSD);
484         result.setUnit(SpeedUnit.METERS_PER_SECOND);
485     }
486 
487     /**
488      * Gets pseudo-range rate measurement noise SD (Standard Deviation).
489      *
490      * @return pseudo-range rate measurement noise SD.
491      */
492     public Speed getSpeedRangeRateSD() {
493         return new Speed(rangeRateSD, SpeedUnit.METERS_PER_SECOND);
494     }
495 
496     /**
497      * Sets pseudo-range rate measurement noise SD (Standard Deviation).
498      *
499      * @param rangeRateSD pseudo-range rate measurement noise SD.
500      */
501     public void setRangeRateSD(final Speed rangeRateSD) {
502         this.rangeRateSD = SpeedConverter.convert(rangeRateSD.getValue().doubleValue(), rangeRateSD.getUnit(),
503                 SpeedUnit.METERS_PER_SECOND);
504     }
505 
506     /**
507      * Sets configuration parameters.
508      *
509      * @param initialPositionUncertainty    initial position uncertainty per axis expressed in
510      *                                      meters (m).
511      * @param initialVelocityUncertainty    initial velocity uncertainty per axis expressed in
512      *                                      meters per second (m/s).
513      * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis expressed in
514      *                                      meters (m).
515      * @param initialClockDriftUncertainty  initial clock drift uncertainty per axis expressed in
516      *                                      meters per second (m/s).
517      * @param accelerationPSD               acceleration PSD (Power Spectral Density) per axis
518      *                                      expressed in (m^2/s^3).
519      * @param clockFrequencyPSD             receiver clock frequency-drift PSD (Power Spectral
520      *                                      Density) expressed in (m^2/s^3).
521      * @param clockPhasePSD                 receiver clock phase-drift PSD (Power Spectral Density)
522      *                                      expressed in (m^2/s).
523      * @param pseudoRangeSD                 pseudo-range measurement noise SD (Standard Deviation)
524      *                                      expressed in meters (m).
525      * @param rangeRateSD                   pseudo-range measurement noise SD (Standard Deviation)
526      *                                      expressed in meters per second (m/s).
527      */
528     public void setValues(final double initialPositionUncertainty,
529                           final double initialVelocityUncertainty,
530                           final double initialClockOffsetUncertainty,
531                           final double initialClockDriftUncertainty,
532                           final double accelerationPSD, final double clockFrequencyPSD,
533                           final double clockPhasePSD, final double pseudoRangeSD,
534                           final double rangeRateSD) {
535         this.initialPositionUncertainty = initialPositionUncertainty;
536         this.initialVelocityUncertainty = initialVelocityUncertainty;
537         this.initialClockOffsetUncertainty = initialClockOffsetUncertainty;
538         this.initialClockDriftUncertainty = initialClockDriftUncertainty;
539         this.accelerationPSD = accelerationPSD;
540         this.clockFrequencyPSD = clockFrequencyPSD;
541         this.clockPhasePSD = clockPhasePSD;
542         this.pseudoRangeSD = pseudoRangeSD;
543         this.rangeRateSD = rangeRateSD;
544     }
545 
546     /**
547      * Sets configuration parameters.
548      *
549      * @param initialPositionUncertainty    initial position uncertainty per axis.
550      * @param initialVelocityUncertainty    initial velocity uncertainty per axis.
551      * @param initialClockOffsetUncertainty initial clock offset uncertainty per axis.
552      * @param initialClockDriftUncertainty  initial clock drift uncertainty per axis.
553      * @param accelerationPSD               acceleration PSD (Power Spectral Density) per axis
554      *                                      expressed in (m^2/s^3).
555      * @param clockFrequencyPSD             receiver clock frequency-drift PSD (Power Spectral
556      *                                      Density) expressed in (m^2/s^3).
557      * @param clockPhasePSD                 receiver clock phase-drift PSD (Power Spectral Density)
558      *                                      expressed in (m^2/s).
559      * @param pseudoRangeSD                 pseudo-range measurement noise SD (Standard Deviation).
560      * @param rangeRateSD                   pseudo-range measurement noise SD (Standard Deviation).
561      */
562     public void setValues(final Distance initialPositionUncertainty, final Speed initialVelocityUncertainty,
563                           final Distance initialClockOffsetUncertainty, final Speed initialClockDriftUncertainty,
564                           final double accelerationPSD, final double clockFrequencyPSD, final double clockPhasePSD,
565                           final Distance pseudoRangeSD, final Speed rangeRateSD) {
566         setInitialPositionUncertainty(initialPositionUncertainty);
567         setInitialVelocityUncertainty(initialVelocityUncertainty);
568         setInitialClockOffsetUncertainty(initialClockOffsetUncertainty);
569         setInitialClockDriftUncertainty(initialClockDriftUncertainty);
570         this.accelerationPSD = accelerationPSD;
571         this.clockFrequencyPSD = clockFrequencyPSD;
572         this.clockPhasePSD = clockPhasePSD;
573         setPseudoRangeSD(pseudoRangeSD);
574         setRangeRateSD(rangeRateSD);
575     }
576 
577     /**
578      * Copies this instance data into provided instance.
579      *
580      * @param output destination instance where data will be copied to.
581      */
582     public void copyTo(final GNSSKalmanConfig output) {
583         output.initialPositionUncertainty = initialPositionUncertainty;
584         output.initialVelocityUncertainty = initialVelocityUncertainty;
585         output.initialClockOffsetUncertainty = initialClockOffsetUncertainty;
586         output.initialClockDriftUncertainty = initialClockDriftUncertainty;
587         output.accelerationPSD = accelerationPSD;
588         output.clockFrequencyPSD = clockFrequencyPSD;
589         output.clockPhasePSD = clockPhasePSD;
590         output.pseudoRangeSD = pseudoRangeSD;
591         output.rangeRateSD = rangeRateSD;
592     }
593 
594     /**
595      * Copies data of provided instance into this instance.
596      *
597      * @param input instance to copy data from.
598      */
599     public void copyFrom(final GNSSKalmanConfig input) {
600         initialPositionUncertainty = input.initialPositionUncertainty;
601         initialVelocityUncertainty = input.initialVelocityUncertainty;
602         initialClockOffsetUncertainty = input.initialClockOffsetUncertainty;
603         initialClockDriftUncertainty = input.initialClockDriftUncertainty;
604         accelerationPSD = input.accelerationPSD;
605         clockFrequencyPSD = input.clockFrequencyPSD;
606         clockPhasePSD = input.clockPhasePSD;
607         pseudoRangeSD = input.pseudoRangeSD;
608         rangeRateSD = input.rangeRateSD;
609     }
610 
611     /**
612      * Computes and returns hash code for this instance. Hash codes are almost unique
613      * values that are useful for fast classification and storage of objects in collections.
614      *
615      * @return Hash code.
616      */
617     @Override
618     public int hashCode() {
619         return Objects.hash(initialPositionUncertainty, initialVelocityUncertainty, initialClockOffsetUncertainty,
620                 initialClockDriftUncertainty, accelerationPSD, clockFrequencyPSD, clockPhasePSD, pseudoRangeSD,
621                 rangeRateSD);
622     }
623 
624     /**
625      * Checks if provided object is a GNSSKalmanConfig having exactly the same contents
626      * as this instance.
627      *
628      * @param obj Object to be compared.
629      * @return true if both objects are considered to be equal, false otherwise.
630      */
631     @Override
632     public boolean equals(final Object obj) {
633         if (obj == this) {
634             return true;
635         }
636         if (obj == null || getClass() != obj.getClass()) {
637             return false;
638         }
639 
640         final var other = (GNSSKalmanConfig) obj;
641         return equals(other);
642     }
643 
644     /**
645      * Checks if provided instance has exactly the same contents as this instance.
646      *
647      * @param other instance to be compared.
648      * @return true if both instances are considered to be equal, false otherwise.
649      */
650     public boolean equals(final GNSSKalmanConfig other) {
651         return equals(other, 0.0);
652     }
653 
654     /**
655      * Checks if provided instance has contents similar to this instance up to provided
656      * threshold value.
657      *
658      * @param other     instance to be compared.
659      * @param threshold maximum difference allowed for values.
660      * @return true if both instances are considered to be equal (up to provided threshold),
661      * false otherwise.
662      */
663     public boolean equals(final GNSSKalmanConfig other, final double threshold) {
664         if (other == null) {
665             return false;
666         }
667 
668         return Math.abs(initialPositionUncertainty - other.initialPositionUncertainty) <= threshold
669                 && Math.abs(initialVelocityUncertainty - other.initialVelocityUncertainty) <= threshold
670                 && Math.abs(initialClockOffsetUncertainty - other.initialClockOffsetUncertainty) <= threshold
671                 && Math.abs(initialClockDriftUncertainty - other.initialClockDriftUncertainty) <= threshold
672                 && Math.abs(accelerationPSD - other.accelerationPSD) <= threshold
673                 && Math.abs(clockFrequencyPSD - other.clockFrequencyPSD) <= threshold
674                 && Math.abs(clockPhasePSD - other.clockPhasePSD) <= threshold
675                 && Math.abs(pseudoRangeSD - other.pseudoRangeSD) <= threshold
676                 && Math.abs(rangeRateSD - other.rangeRateSD) <= threshold;
677     }
678 
679     /**
680      * Makes a copy of this instance.
681      *
682      * @return a copy of this instance.
683      * @throws CloneNotSupportedException if clone fails for some reason.
684      */
685     @Override
686     protected Object clone() throws CloneNotSupportedException {
687         final var result = (GNSSKalmanConfig)super.clone();
688         copyTo(result);
689         return result;
690     }
691 }