KalmanModel.java

  1. /* Copyright 2002-2025 CS GROUP
  2.  * Licensed to CS GROUP (CS) under one or more
  3.  * contributor license agreements.  See the NOTICE file distributed with
  4.  * this work for additional information regarding copyright ownership.
  5.  * CS licenses this file to You under the Apache License, Version 2.0
  6.  * (the "License"); you may not use this file except in compliance with
  7.  * the License.  You may obtain a copy of the License at
  8.  *
  9.  *   http://www.apache.org/licenses/LICENSE-2.0
  10.  *
  11.  * Unless required by applicable law or agreed to in writing, software
  12.  * distributed under the License is distributed on an "AS IS" BASIS,
  13.  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  14.  * See the License for the specific language governing permissions and
  15.  * limitations under the License.
  16.  */
  17. package org.orekit.estimation.sequential;

  18. import org.hipparchus.filtering.kalman.ProcessEstimate;
  19. import org.hipparchus.filtering.kalman.extended.NonLinearEvolution;
  20. import org.hipparchus.filtering.kalman.extended.NonLinearProcess;
  21. import org.hipparchus.linear.Array2DRowRealMatrix;
  22. import org.hipparchus.linear.MatrixUtils;
  23. import org.hipparchus.linear.RealMatrix;
  24. import org.hipparchus.linear.RealVector;
  25. import org.orekit.estimation.measurements.EstimatedMeasurement;
  26. import org.orekit.estimation.measurements.ObservedMeasurement;
  27. import org.orekit.orbits.Orbit;
  28. import org.orekit.propagation.MatricesHarvester;
  29. import org.orekit.propagation.Propagator;
  30. import org.orekit.propagation.SpacecraftState;
  31. import org.orekit.propagation.conversion.AbstractPropagatorBuilder;
  32. import org.orekit.propagation.conversion.PropagatorBuilder;
  33. import org.orekit.time.AbsoluteDate;
  34. import org.orekit.utils.ParameterDriver;
  35. import org.orekit.utils.ParameterDriversList;
  36. import org.orekit.utils.ParameterDriversList.DelegatingDriver;

  37. import java.util.List;
  38. import java.util.Map;

  39. /** Class defining the process model dynamics to use with a {@link KalmanEstimator}.
  40.  * @author Romain Gerbaud
  41.  * @author Maxime Journot
  42.  * @since 9.2
  43.  */
  44. public class KalmanModel extends AbstractKalmanEstimationCommon implements NonLinearProcess<MeasurementDecorator> {


  45.     /** Harvesters for extracting Jacobians from integrated states. */
  46.     private MatricesHarvester[] harvesters;

  47.     /** Propagators for the reference trajectories, up to current date. */
  48.     private Propagator[] referenceTrajectories;

  49.     /** Kalman process model constructor.
  50.      * @param propagatorBuilders propagators builders used to evaluate the orbits.
  51.      * @param covarianceMatricesProviders providers for covariance matrices
  52.      * @param estimatedMeasurementParameters measurement parameters to estimate
  53.      * @param measurementProcessNoiseMatrix provider for measurement process noise matrix
  54.      */
  55.     public KalmanModel(final List<PropagatorBuilder> propagatorBuilders,
  56.                        final List<CovarianceMatrixProvider> covarianceMatricesProviders,
  57.                        final ParameterDriversList estimatedMeasurementParameters,
  58.                        final CovarianceMatrixProvider measurementProcessNoiseMatrix) {
  59.         super(propagatorBuilders, covarianceMatricesProviders, estimatedMeasurementParameters, measurementProcessNoiseMatrix);
  60.         // Build the reference propagators and add their partial derivatives equations implementation
  61.         updateReferenceTrajectories(getEstimatedPropagators());
  62.     }

  63.     /** Update the reference trajectories using the propagators as input.
  64.      * @param propagators The new propagators to use
  65.      */
  66.     protected void updateReferenceTrajectories(final Propagator[] propagators) {

  67.         // Update the reference trajectory propagator
  68.         setReferenceTrajectories(propagators);

  69.         // Jacobian harvesters
  70.         harvesters = new MatricesHarvester[propagators.length];

  71.         for (int k = 0; k < propagators.length; ++k) {
  72.             // Link the partial derivatives to this new propagator
  73.             final String equationName = KalmanEstimator.class.getName() + "-derivatives-" + k;
  74.             harvesters[k] = getReferenceTrajectories()[k].setupMatricesComputation(equationName, null, null);
  75.         }

  76.     }

  77.     /** Get the normalized error state transition matrix (STM) from previous point to current point.
  78.      * The STM contains the partial derivatives of current state with respect to previous state.
  79.      * The  STM is an mxm matrix where m is the size of the state vector.
  80.      * m = nbOrb + nbPropag + nbMeas
  81.      * @return the normalized error state transition matrix
  82.      */
  83.     private RealMatrix getErrorStateTransitionMatrix() {

  84.         /* The state transition matrix is obtained as follows, with:
  85.          *  - Y  : Current state vector
  86.          *  - Y0 : Initial state vector
  87.          *  - Pp : Current propagation parameter
  88.          *  - Pp0: Initial propagation parameter
  89.          *  - Mp : Current measurement parameter
  90.          *  - Mp0: Initial measurement parameter
  91.          *
  92.          *       |        |         |         |   |        |        |   .    |
  93.          *       | dY/dY0 | dY/dPp  | dY/dMp  |   | dY/dY0 | dY/dPp | ..0..  |
  94.          *       |        |         |         |   |        |        |   .    |
  95.          *       |--------|---------|---------|   |--------|--------|--------|
  96.          *       |        |         |         |   |   .    | 1 0 0..|   .    |
  97.          * STM = | dP/dY0 | dP/dPp0 | dP/dMp  | = | ..0..  | 0 1 0..| ..0..  |
  98.          *       |        |         |         |   |   .    | 0 0 1..|   .    |
  99.          *       |--------|---------|---------|   |--------|--------|--------|
  100.          *       |        |         |         |   |   .    |   .    | 1 0 0..|
  101.          *       | dM/dY0 | dM/dPp0 | dM/dMp0 |   | ..0..  | ..0..  | 0 1 0..|
  102.          *       |        |         |         |   |   .    |   .    | 0 0 1..|
  103.          */

  104.         // Initialize to the proper size identity matrix
  105.         final RealMatrix stm = MatrixUtils.createRealIdentityMatrix(getCorrectedEstimate().getState().getDimension());

  106.         // loop over all orbits
  107.         final SpacecraftState[] predictedSpacecraftStates = getPredictedSpacecraftStates();
  108.         final int[][] covarianceIndirection = getCovarianceIndirection();
  109.         final ParameterDriversList[] estimatedOrbitalParameters = getEstimatedOrbitalParametersArray();
  110.         final ParameterDriversList[] estimatedPropagationParameters = getEstimatedPropagationParametersArray();
  111.         final double[] scale = getScale();
  112.         for (int k = 0; k < predictedSpacecraftStates.length; ++k) {

  113.             // Orbital drivers
  114.             final List<DelegatingDriver> orbitalParameterDrivers =
  115.                     getBuilders().get(k).getOrbitalParametersDrivers().getDrivers();

  116.             // Indexes
  117.             final int[] indK = covarianceIndirection[k];

  118.             // Derivatives of the state vector with respect to initial state vector
  119.             final int nbOrbParams = estimatedOrbitalParameters[k].getNbParams();
  120.             if (nbOrbParams > 0) {

  121.                 // Reset reference (for example compute short periodic terms in DSST)
  122.                 harvesters[k].setReferenceState(predictedSpacecraftStates[k]);

  123.                 final RealMatrix dYdY0 = harvesters[k].getStateTransitionMatrix(predictedSpacecraftStates[k]);

  124.                 // Fill upper left corner (dY/dY0)
  125.                 int stmRow = 0;
  126.                 for (int i = 0; i < dYdY0.getRowDimension(); ++i) {
  127.                     int stmCol = 0;
  128.                     if (orbitalParameterDrivers.get(i).isSelected()) {
  129.                         for (int j = 0; j < nbOrbParams; ++j) {
  130.                             if (orbitalParameterDrivers.get(j).isSelected()) {
  131.                                 stm.setEntry(indK[stmRow], indK[stmCol], dYdY0.getEntry(i, j));
  132.                                 stmCol += 1;
  133.                             }
  134.                         }
  135.                         stmRow += 1;
  136.                     }
  137.                 }
  138.             }

  139.             // Derivatives of the state vector with respect to propagation parameters
  140.             final int nbParams = estimatedPropagationParameters[k].getNbParams();
  141.             if (nbOrbParams > 0 && nbParams > 0) {
  142.                 final RealMatrix dYdPp = harvesters[k].getParametersJacobian(predictedSpacecraftStates[k]);

  143.                 // Fill 1st row, 2nd column (dY/dPp)
  144.                 int stmRow = 0;
  145.                 for (int i = 0; i < dYdPp.getRowDimension(); ++i) {
  146.                     if (orbitalParameterDrivers.get(i).isSelected()) {
  147.                         for (int j = 0; j < nbParams; ++j) {
  148.                             stm.setEntry(indK[stmRow], indK[j + nbOrbParams], dYdPp.getEntry(i, j));
  149.                         }
  150.                         stmRow += 1;
  151.                     }
  152.                 }

  153.             }

  154.         }

  155.         // Normalization of the STM
  156.         // normalized(STM)ij = STMij*Sj/Si
  157.         for (int i = 0; i < scale.length; i++) {
  158.             for (int j = 0; j < scale.length; j++ ) {
  159.                 stm.setEntry(i, j, stm.getEntry(i, j) * scale[j] / scale[i]);
  160.             }
  161.         }

  162.         // Return the error state transition matrix
  163.         return stm;

  164.     }

  165.     /** Get the normalized measurement matrix H.
  166.      * H contains the partial derivatives of the measurement with respect to the state.
  167.      * H is an nxm matrix where n is the size of the measurement vector and m the size of the state vector.
  168.      * @return the normalized measurement matrix H
  169.      */
  170.     private RealMatrix getMeasurementMatrix() {

  171.         // Observed measurement characteristics
  172.         final EstimatedMeasurement<?> predictedMeasurement = getPredictedMeasurement();
  173.         final SpacecraftState[]      evaluationStates    = predictedMeasurement.getStates();
  174.         final ObservedMeasurement<?> observedMeasurement = predictedMeasurement.getObservedMeasurement();
  175.         final double[] sigma  = observedMeasurement.getTheoreticalStandardDeviation();

  176.         // Initialize measurement matrix H: nxm
  177.         // n: Number of measurements in current measurement
  178.         // m: State vector size
  179.         final RealMatrix measurementMatrix = MatrixUtils.
  180.                         createRealMatrix(observedMeasurement.getDimension(),
  181.                                          getCorrectedEstimate().getState().getDimension());

  182.         // loop over all orbits involved in the measurement
  183.         final int[] orbitsStartColumns = getOrbitsStartColumns();
  184.         final ParameterDriversList[] estimatedPropagationParameters = getEstimatedPropagationParametersArray();
  185.         final Map<String, Integer> propagationParameterColumns = getPropagationParameterColumns();
  186.         final Map<String, Integer> measurementParameterColumns = getMeasurementParameterColumns();
  187.         for (int k = 0; k < evaluationStates.length; ++k) {
  188.             final int p = observedMeasurement.getSatellites().get(k).getPropagatorIndex();

  189.             // Predicted orbit
  190.             final Orbit predictedOrbit = evaluationStates[k].getOrbit();

  191.             // Measurement matrix's columns related to orbital parameters
  192.             // ----------------------------------------------------------

  193.             // Partial derivatives of the current Cartesian coordinates with respect to current orbital state
  194.             final double[][] aCY = new double[6][6];
  195.             predictedOrbit.getJacobianWrtParameters(getBuilders().get(p).getPositionAngleType(), aCY);   //dC/dY
  196.             final RealMatrix dCdY = new Array2DRowRealMatrix(aCY, false);

  197.             // Jacobian of the measurement with respect to current Cartesian coordinates
  198.             final RealMatrix dMdC = new Array2DRowRealMatrix(predictedMeasurement.getStateDerivatives(k), false);

  199.             // Jacobian of the measurement with respect to current orbital state
  200.             final RealMatrix dMdY = dMdC.multiply(dCdY);

  201.             // Fill the normalized measurement matrix's columns related to estimated orbital parameters
  202.             for (int i = 0; i < dMdY.getRowDimension(); ++i) {
  203.                 int jOrb = orbitsStartColumns[p];
  204.                 for (int j = 0; j < dMdY.getColumnDimension(); ++j) {
  205.                     final ParameterDriver driver = getBuilders().get(p).getOrbitalParametersDrivers().getDrivers().get(j);
  206.                     if (driver.isSelected()) {
  207.                         measurementMatrix.setEntry(i, jOrb++,
  208.                                                    dMdY.getEntry(i, j) / sigma[i] * driver.getScale());
  209.                     }
  210.                 }
  211.             }

  212.             // Normalized measurement matrix's columns related to propagation parameters
  213.             // --------------------------------------------------------------

  214.             // Jacobian of the measurement with respect to propagation parameters
  215.             final int nbParams = estimatedPropagationParameters[p].getNbParams();
  216.             if (nbParams > 0) {
  217.                 final RealMatrix dYdPp = harvesters[p].getParametersJacobian(evaluationStates[k]);
  218.                 final RealMatrix dMdPp = dMdY.multiply(dYdPp);
  219.                 for (int i = 0; i < dMdPp.getRowDimension(); ++i) {
  220.                     for (int j = 0; j < nbParams; ++j) {
  221.                         final ParameterDriver delegating = estimatedPropagationParameters[p].getDrivers().get(j);
  222.                         measurementMatrix.setEntry(i, propagationParameterColumns.get(delegating.getName()),
  223.                                                    dMdPp.getEntry(i, j) / sigma[i] * delegating.getScale());
  224.                     }
  225.                 }
  226.             }

  227.             // Normalized measurement matrix's columns related to measurement parameters
  228.             // --------------------------------------------------------------

  229.             // Jacobian of the measurement with respect to measurement parameters
  230.             // Gather the measurement parameters linked to current measurement
  231.             for (final ParameterDriver driver : observedMeasurement.getParametersDrivers()) {
  232.                 if (driver.isSelected()) {
  233.                     // Derivatives of current measurement w/r to selected measurement parameter
  234.                     final double[] aMPm = predictedMeasurement.getParameterDerivatives(driver);

  235.                     // Check that the measurement parameter is managed by the filter
  236.                     if (measurementParameterColumns.get(driver.getName()) != null) {
  237.                         // Column of the driver in the measurement matrix
  238.                         final int driverColumn = measurementParameterColumns.get(driver.getName());

  239.                         // Fill the corresponding indexes of the measurement matrix
  240.                         for (int i = 0; i < aMPm.length; ++i) {
  241.                             measurementMatrix.setEntry(i, driverColumn,
  242.                                                        aMPm[i] / sigma[i] * driver.getScale());
  243.                         }
  244.                     }
  245.                 }
  246.             }
  247.         }

  248.         // Return the normalized measurement matrix
  249.         return measurementMatrix;

  250.     }

  251.     /** {@inheritDoc} */
  252.     @Override
  253.     public NonLinearEvolution getEvolution(final double previousTime, final RealVector previousState,
  254.                                            final MeasurementDecorator measurement) {

  255.         // Set a reference date for all measurements parameters that lack one (including the not estimated ones)
  256.         final ObservedMeasurement<?> observedMeasurement = measurement.getObservedMeasurement();
  257.         for (final ParameterDriver driver : observedMeasurement.getParametersDrivers()) {
  258.             if (driver.getReferenceDate() == null) {
  259.                 driver.setReferenceDate(getBuilders().get(0).getInitialOrbitDate());
  260.             }
  261.         }

  262.         incrementCurrentMeasurementNumber();
  263.         setCurrentDate(measurement.getObservedMeasurement().getDate());

  264.         // Note:
  265.         // - n = size of the current measurement
  266.         //  Example:
  267.         //   * 1 for Range, RangeRate and TurnAroundRange
  268.         //   * 2 for Angular (Azimuth/Elevation or Right-ascension/Declination)
  269.         //   * 6 for Position/Velocity
  270.         // - m = size of the state vector. n = nbOrb + nbPropag + nbMeas

  271.         // Predict the state vector (mx1)
  272.         final RealVector predictedState = predictState(observedMeasurement.getDate());

  273.         // Get the error state transition matrix (mxm)
  274.         final RealMatrix stateTransitionMatrix = getErrorStateTransitionMatrix();

  275.         // Predict the measurement based on predicted spacecraft state
  276.         // Compute the innovations (i.e. residuals of the predicted measurement)
  277.         // ------------------------------------------------------------

  278.         // Predicted measurement
  279.         // Note: here the "iteration/evaluation" formalism from the batch LS method
  280.         // is twisted to fit the need of the Kalman filter.
  281.         // The number of "iterations" is actually the number of measurements processed by the filter
  282.         // so far. We use this to be able to apply the OutlierFilter modifiers on the predicted measurement.
  283.         setPredictedMeasurement(observedMeasurement.estimate(getCurrentMeasurementNumber(),
  284.                                                              getCurrentMeasurementNumber(),
  285.                                                              KalmanEstimatorUtil.filterRelevant(observedMeasurement, getPredictedSpacecraftStates())));

  286.         // Normalized measurement matrix (nxm)
  287.         final RealMatrix measurementMatrix = getMeasurementMatrix();

  288.         // compute process noise matrix
  289.         final RealMatrix normalizedProcessNoise = getNormalizedProcessNoise(previousState.getDimension());

  290.         return new NonLinearEvolution(measurement.getTime(), predictedState,
  291.                                       stateTransitionMatrix, normalizedProcessNoise, measurementMatrix);
  292.     }


  293.     /** {@inheritDoc} */
  294.     @Override
  295.     public RealVector getInnovation(final MeasurementDecorator measurement, final NonLinearEvolution evolution,
  296.                                     final RealMatrix innovationCovarianceMatrix) {

  297.         // Apply the dynamic outlier filter, if it exists
  298.         final EstimatedMeasurement<?> predictedMeasurement = getPredictedMeasurement();
  299.         KalmanEstimatorUtil.applyDynamicOutlierFilter(predictedMeasurement, innovationCovarianceMatrix);
  300.         // Compute the innovation vector
  301.         return KalmanEstimatorUtil.computeInnovationVector(predictedMeasurement, predictedMeasurement.getObservedMeasurement().getTheoreticalStandardDeviation());
  302.     }

  303.     /** Finalize estimation.
  304.      * @param observedMeasurement measurement that has just been processed
  305.      * @param estimate corrected estimate
  306.      */
  307.     public void finalizeEstimation(final ObservedMeasurement<?> observedMeasurement,
  308.                                    final ProcessEstimate estimate) {
  309.         // Update the parameters with the estimated state
  310.         // The min/max values of the parameters are handled by the ParameterDriver implementation
  311.         setCorrectedEstimate(estimate);
  312.         updateParameters();

  313.         // Get the estimated propagator (mirroring parameter update in the builder)
  314.         // and the estimated spacecraft state
  315.         final Propagator[] estimatedPropagators = getEstimatedPropagators();
  316.         for (int k = 0; k < estimatedPropagators.length; ++k) {
  317.             setCorrectedSpacecraftState(estimatedPropagators[k].getInitialState(), k);
  318.         }

  319.         // Compute the estimated measurement using estimated spacecraft state
  320.         setCorrectedMeasurement(observedMeasurement.estimate(getCurrentMeasurementNumber(),
  321.                                                              getCurrentMeasurementNumber(),
  322.                                                              KalmanEstimatorUtil.filterRelevant(observedMeasurement, getCorrectedSpacecraftStates())));
  323.         // Update the trajectory
  324.         // ---------------------
  325.         updateReferenceTrajectories(estimatedPropagators);

  326.     }

  327.     /** Set the predicted normalized state vector.
  328.      * The predicted/propagated orbit is used to update the state vector
  329.      * @param date prediction date
  330.      * @return predicted state
  331.      */
  332.     private RealVector predictState(final AbsoluteDate date) {

  333.         // Predicted state is initialized to previous estimated state
  334.         final RealVector predictedState = getCorrectedEstimate().getState().copy();

  335.         // Orbital parameters counter
  336.         int jOrb = 0;

  337.         for (int k = 0; k < getPredictedSpacecraftStates().length; ++k) {

  338.             // Propagate the reference trajectory to measurement date
  339.             final SpacecraftState predictedSpacecraftState = referenceTrajectories[k].propagate(date);
  340.             setPredictedSpacecraftState(predictedSpacecraftState, k);

  341.             // Update the builder with the predicted orbit
  342.             // This updates the orbital drivers with the values of the predicted orbit
  343.             getBuilders().get(k).resetOrbit(predictedSpacecraftState.getOrbit());

  344.             // Additionally, for PropagatorBuilders which use mass, update the builder with the predicted mass value.
  345.             // If any mass changes have occurred during this estimation step, such as maneuvers,
  346.             // the updated mass value must be carried over so that new Propagators from this builder start with the updated mass.
  347.             if (getBuilders().get(k) instanceof AbstractPropagatorBuilder) {
  348.                 ((AbstractPropagatorBuilder<?>) (getBuilders().get(k))).setMass(predictedSpacecraftState.getMass());
  349.             }

  350.             // The orbital parameters in the state vector are replaced with their predicted values
  351.             // The propagation & measurement parameters are not changed by the prediction (i.e. the propagation)
  352.             // As the propagator builder was previously updated with the predicted orbit,
  353.             // the selected orbital drivers are already up to date with the prediction
  354.             for (DelegatingDriver orbitalDriver : getBuilders().get(k).getOrbitalParametersDrivers().getDrivers()) {
  355.                 if (orbitalDriver.isSelected()) {
  356.                     predictedState.setEntry(jOrb++, orbitalDriver.getNormalizedValue());
  357.                 }
  358.             }

  359.         }

  360.         return predictedState;

  361.     }

  362.     /** Update the estimated parameters after the correction phase of the filter.
  363.      * The min/max allowed values are handled by the parameter themselves.
  364.      */
  365.     private void updateParameters() {
  366.         final RealVector correctedState = getCorrectedEstimate().getState();
  367.         int i = 0;
  368.         for (final DelegatingDriver driver : getEstimatedOrbitalParameters().getDrivers()) {
  369.             // let the parameter handle min/max clipping
  370.             driver.setNormalizedValue(correctedState.getEntry(i));
  371.             correctedState.setEntry(i++, driver.getNormalizedValue());
  372.         }
  373.         for (final DelegatingDriver driver : getEstimatedPropagationParameters().getDrivers()) {
  374.             // let the parameter handle min/max clipping
  375.             driver.setNormalizedValue(correctedState.getEntry(i));
  376.             correctedState.setEntry(i++, driver.getNormalizedValue());
  377.         }
  378.         for (final DelegatingDriver driver : getEstimatedMeasurementsParameters().getDrivers()) {
  379.             // let the parameter handle min/max clipping
  380.             driver.setNormalizedValue(correctedState.getEntry(i));
  381.             correctedState.setEntry(i++, driver.getNormalizedValue());
  382.         }
  383.     }

  384.     /** Getter for the reference trajectories.
  385.      * @return the referencetrajectories
  386.      */
  387.     public Propagator[] getReferenceTrajectories() {
  388.         return referenceTrajectories.clone();
  389.     }

  390.     /** Setter for the reference trajectories.
  391.      * @param referenceTrajectories the reference trajectories to be setted
  392.      */
  393.     public void setReferenceTrajectories(final Propagator[] referenceTrajectories) {
  394.         this.referenceTrajectories = referenceTrajectories.clone();
  395.     }

  396. }