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.propagation.numerical.NumericalPropagator;
  34. import org.orekit.time.AbsoluteDate;
  35. import org.orekit.utils.ParameterDriver;
  36. import org.orekit.utils.ParameterDriversList;
  37. import org.orekit.utils.ParameterDriversList.DelegatingDriver;

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

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


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

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

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

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

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

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

  72.         for (int k = 0; k < propagators.length; ++k) {
  73.             // Link the partial derivatives to this new propagator
  74.             final String equationName = KalmanEstimator.class.getName() + "-derivatives-" + k;
  75.             final Propagator propagator = getReferenceTrajectories()[k];
  76.             final RealMatrix initialStm;
  77.             if (propagator instanceof NumericalPropagator) {
  78.                 initialStm = MatrixUtils.createRealIdentityMatrix(7);
  79.             } else {
  80.                 initialStm = MatrixUtils.createRealIdentityMatrix(6);
  81.             }
  82.             harvesters[k] = propagator.setupMatricesComputation(equationName, initialStm, null);
  83.         }

  84.     }

  85.     /** Get the normalized error state transition matrix (STM) from previous point to current point.
  86.      * The STM contains the partial derivatives of current state with respect to previous state.
  87.      * The  STM is an mxm matrix where m is the size of the state vector.
  88.      * m = nbOrb + nbPropag + nbMeas
  89.      * @return the normalized error state transition matrix
  90.      */
  91.     private RealMatrix getErrorStateTransitionMatrix() {

  92.         /* The state transition matrix is obtained as follows, with:
  93.          *  - Y  : Current state vector
  94.          *  - Y0 : Initial state vector
  95.          *  - Pp : Current propagation parameter
  96.          *  - Pp0: Initial propagation parameter
  97.          *  - Mp : Current measurement parameter
  98.          *  - Mp0: Initial measurement parameter
  99.          *
  100.          *       |        |         |         |   |        |        |   .    |
  101.          *       | dY/dY0 | dY/dPp  | dY/dMp  |   | dY/dY0 | dY/dPp | ..0..  |
  102.          *       |        |         |         |   |        |        |   .    |
  103.          *       |--------|---------|---------|   |--------|--------|--------|
  104.          *       |        |         |         |   |   .    | 1 0 0..|   .    |
  105.          * STM = | dP/dY0 | dP/dPp0 | dP/dMp  | = | ..0..  | 0 1 0..| ..0..  |
  106.          *       |        |         |         |   |   .    | 0 0 1..|   .    |
  107.          *       |--------|---------|---------|   |--------|--------|--------|
  108.          *       |        |         |         |   |   .    |   .    | 1 0 0..|
  109.          *       | dM/dY0 | dM/dPp0 | dM/dMp0 |   | ..0..  | ..0..  | 0 1 0..|
  110.          *       |        |         |         |   |   .    |   .    | 0 0 1..|
  111.          */

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

  114.         // loop over all orbits
  115.         final SpacecraftState[] predictedSpacecraftStates = getPredictedSpacecraftStates();
  116.         final int[][] covarianceIndirection = getCovarianceIndirection();
  117.         final ParameterDriversList[] estimatedOrbitalParameters = getEstimatedOrbitalParametersArray();
  118.         final ParameterDriversList[] estimatedPropagationParameters = getEstimatedPropagationParametersArray();
  119.         final double[] scale = getScale();
  120.         for (int k = 0; k < predictedSpacecraftStates.length; ++k) {

  121.             // Orbital drivers
  122.             final List<DelegatingDriver> orbitalParameterDrivers =
  123.                     getBuilders().get(k).getOrbitalParametersDrivers().getDrivers();

  124.             // Indexes
  125.             final int[] indK = covarianceIndirection[k];

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

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

  131.                 RealMatrix dYdY0 = harvesters[k].getStateTransitionMatrix(predictedSpacecraftStates[k]);
  132.                 if (dYdY0.getRowDimension() == 7) {
  133.                     // mass was included in STM propagation, removed it now
  134.                     dYdY0 = dYdY0.getSubMatrix(0, 5, 0, 5);
  135.                 }

  136.                 // Fill upper left corner (dY/dY0)
  137.                 int stmRow = 0;
  138.                 for (int i = 0; i < dYdY0.getRowDimension(); ++i) {
  139.                     int stmCol = 0;
  140.                     if (orbitalParameterDrivers.get(i).isSelected()) {
  141.                         for (int j = 0; j < nbOrbParams; ++j) {
  142.                             if (orbitalParameterDrivers.get(j).isSelected()) {
  143.                                 stm.setEntry(indK[stmRow], indK[stmCol], dYdY0.getEntry(i, j));
  144.                                 stmCol += 1;
  145.                             }
  146.                         }
  147.                         stmRow += 1;
  148.                     }
  149.                 }
  150.             }

  151.             // Derivatives of the state vector with respect to propagation parameters
  152.             final int nbParams = estimatedPropagationParameters[k].getNbParams();
  153.             if (nbOrbParams > 0 && nbParams > 0) {
  154.                 final RealMatrix dYdPp = getParametersJacobian(harvesters[k], predictedSpacecraftStates[k]);

  155.                 // Fill 1st row, 2nd column (dY/dPp)
  156.                 int stmRow = 0;
  157.                 for (int i = 0; i < dYdPp.getRowDimension(); ++i) {
  158.                     if (orbitalParameterDrivers.get(i).isSelected()) {
  159.                         for (int j = 0; j < nbParams; ++j) {
  160.                             stm.setEntry(indK[stmRow], indK[j + nbOrbParams], dYdPp.getEntry(i, j));
  161.                         }
  162.                         stmRow += 1;
  163.                     }
  164.                 }

  165.             }

  166.         }

  167.         // Normalization of the STM
  168.         // normalized(STM)ij = STMij*Sj/Si
  169.         for (int i = 0; i < scale.length; i++) {
  170.             for (int j = 0; j < scale.length; j++ ) {
  171.                 stm.setEntry(i, j, stm.getEntry(i, j) * scale[j] / scale[i]);
  172.             }
  173.         }

  174.         // Return the error state transition matrix
  175.         return stm;

  176.     }

  177.     /**
  178.      * Extract Jacobian matrix of state w.r.t. model parameter.
  179.      * @param harvester matrix harvester
  180.      * @param state state
  181.      * @return jacobian matrix
  182.      * @since 13.1
  183.      */
  184.     private RealMatrix getParametersJacobian(final MatricesHarvester harvester, final SpacecraftState state) {
  185.         RealMatrix dYdP = harvester.getParametersJacobian(state);
  186.         if (dYdP.getRowDimension() == 7) {
  187.             // mass was included in STM propagation, removed it now
  188.             dYdP = dYdP.getSubMatrix(0, 5, 0, dYdP.getColumnDimension() - 1);
  189.         }
  190.         return dYdP;
  191.     }

  192.     /** Get the normalized measurement matrix H.
  193.      * H contains the partial derivatives of the measurement with respect to the state.
  194.      * H is an nxm matrix where n is the size of the measurement vector and m the size of the state vector.
  195.      * @return the normalized measurement matrix H
  196.      */
  197.     private RealMatrix getMeasurementMatrix() {

  198.         // Observed measurement characteristics
  199.         final EstimatedMeasurement<?> predictedMeasurement = getPredictedMeasurement();
  200.         final SpacecraftState[]      evaluationStates    = predictedMeasurement.getStates();
  201.         final ObservedMeasurement<?> observedMeasurement = predictedMeasurement.getObservedMeasurement();
  202.         final double[] sigma  = observedMeasurement.getTheoreticalStandardDeviation();

  203.         // Initialize measurement matrix H: nxm
  204.         // n: Number of measurements in current measurement
  205.         // m: State vector size
  206.         final RealMatrix measurementMatrix = MatrixUtils.
  207.                         createRealMatrix(observedMeasurement.getDimension(),
  208.                                          getCorrectedEstimate().getState().getDimension());

  209.         // loop over all orbits involved in the measurement
  210.         final int[] orbitsStartColumns = getOrbitsStartColumns();
  211.         final ParameterDriversList[] estimatedPropagationParameters = getEstimatedPropagationParametersArray();
  212.         final Map<String, Integer> propagationParameterColumns = getPropagationParameterColumns();
  213.         final Map<String, Integer> measurementParameterColumns = getMeasurementParameterColumns();
  214.         for (int k = 0; k < evaluationStates.length; ++k) {
  215.             final int p = observedMeasurement.getSatellites().get(k).getPropagatorIndex();

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

  218.             // Measurement matrix's columns related to orbital parameters
  219.             // ----------------------------------------------------------

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

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

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

  228.             // Fill the normalized measurement matrix's columns related to estimated orbital parameters
  229.             for (int i = 0; i < dMdY.getRowDimension(); ++i) {
  230.                 int jOrb = orbitsStartColumns[p];
  231.                 for (int j = 0; j < dMdY.getColumnDimension(); ++j) {
  232.                     final ParameterDriver driver = getBuilders().get(p).getOrbitalParametersDrivers().getDrivers().get(j);
  233.                     if (driver.isSelected()) {
  234.                         measurementMatrix.setEntry(i, jOrb++,
  235.                                                    dMdY.getEntry(i, j) / sigma[i] * driver.getScale());
  236.                     }
  237.                 }
  238.             }

  239.             // Normalized measurement matrix's columns related to propagation parameters
  240.             // --------------------------------------------------------------

  241.             // Jacobian of the measurement with respect to propagation parameters
  242.             final int nbParams = estimatedPropagationParameters[p].getNbParams();
  243.             if (nbParams > 0) {
  244.                 final RealMatrix dYdPp = getParametersJacobian(harvesters[p], evaluationStates[k]);
  245.                 final RealMatrix dMdPp = dMdY.multiply(dYdPp);
  246.                 for (int i = 0; i < dMdPp.getRowDimension(); ++i) {
  247.                     for (int j = 0; j < nbParams; ++j) {
  248.                         final ParameterDriver delegating = estimatedPropagationParameters[p].getDrivers().get(j);
  249.                         measurementMatrix.setEntry(i, propagationParameterColumns.get(delegating.getName()),
  250.                                                    dMdPp.getEntry(i, j) / sigma[i] * delegating.getScale());
  251.                     }
  252.                 }
  253.             }

  254.             // Normalized measurement matrix's columns related to measurement parameters
  255.             // --------------------------------------------------------------

  256.             // Jacobian of the measurement with respect to measurement parameters
  257.             // Gather the measurement parameters linked to current measurement
  258.             for (final ParameterDriver driver : observedMeasurement.getParametersDrivers()) {
  259.                 if (driver.isSelected()) {
  260.                     // Derivatives of current measurement w/r to selected measurement parameter
  261.                     final double[] aMPm = predictedMeasurement.getParameterDerivatives(driver);

  262.                     // Check that the measurement parameter is managed by the filter
  263.                     if (measurementParameterColumns.get(driver.getName()) != null) {
  264.                         // Column of the driver in the measurement matrix
  265.                         final int driverColumn = measurementParameterColumns.get(driver.getName());

  266.                         // Fill the corresponding indexes of the measurement matrix
  267.                         for (int i = 0; i < aMPm.length; ++i) {
  268.                             measurementMatrix.setEntry(i, driverColumn,
  269.                                                        aMPm[i] / sigma[i] * driver.getScale());
  270.                         }
  271.                     }
  272.                 }
  273.             }
  274.         }

  275.         // Return the normalized measurement matrix
  276.         return measurementMatrix;

  277.     }

  278.     /** {@inheritDoc} */
  279.     @Override
  280.     public NonLinearEvolution getEvolution(final double previousTime, final RealVector previousState,
  281.                                            final MeasurementDecorator measurement) {

  282.         // Set a reference date for all measurements parameters that lack one (including the not estimated ones)
  283.         final ObservedMeasurement<?> observedMeasurement = measurement.getObservedMeasurement();
  284.         for (final ParameterDriver driver : observedMeasurement.getParametersDrivers()) {
  285.             if (driver.getReferenceDate() == null) {
  286.                 driver.setReferenceDate(getBuilders().get(0).getInitialOrbitDate());
  287.             }
  288.         }

  289.         incrementCurrentMeasurementNumber();
  290.         setCurrentDate(measurement.getObservedMeasurement().getDate());

  291.         // Note:
  292.         // - n = size of the current measurement
  293.         //  Example:
  294.         //   * 1 for Range, RangeRate and TurnAroundRange
  295.         //   * 2 for Angular (Azimuth/Elevation or Right-ascension/Declination)
  296.         //   * 6 for Position/Velocity
  297.         // - m = size of the state vector. n = nbOrb + nbPropag + nbMeas

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

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

  302.         // Predict the measurement based on predicted spacecraft state
  303.         // Compute the innovations (i.e. residuals of the predicted measurement)
  304.         // ------------------------------------------------------------

  305.         // Predicted measurement
  306.         // Note: here the "iteration/evaluation" formalism from the batch LS method
  307.         // is twisted to fit the need of the Kalman filter.
  308.         // The number of "iterations" is actually the number of measurements processed by the filter
  309.         // so far. We use this to be able to apply the OutlierFilter modifiers on the predicted measurement.
  310.         setPredictedMeasurement(observedMeasurement.estimate(getCurrentMeasurementNumber(),
  311.                                                              getCurrentMeasurementNumber(),
  312.                                                              KalmanEstimatorUtil.filterRelevant(observedMeasurement, getPredictedSpacecraftStates())));

  313.         // Normalized measurement matrix (nxm)
  314.         final RealMatrix measurementMatrix = getMeasurementMatrix();

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

  317.         return new NonLinearEvolution(measurement.getTime(), predictedState,
  318.                                       stateTransitionMatrix, normalizedProcessNoise, measurementMatrix);
  319.     }


  320.     /** {@inheritDoc} */
  321.     @Override
  322.     public RealVector getInnovation(final MeasurementDecorator measurement, final NonLinearEvolution evolution,
  323.                                     final RealMatrix innovationCovarianceMatrix) {

  324.         // Apply the dynamic outlier filter, if it exists
  325.         final EstimatedMeasurement<?> predictedMeasurement = getPredictedMeasurement();
  326.         KalmanEstimatorUtil.applyDynamicOutlierFilter(predictedMeasurement, innovationCovarianceMatrix);
  327.         // Compute the innovation vector
  328.         return KalmanEstimatorUtil.computeInnovationVector(predictedMeasurement, predictedMeasurement.getObservedMeasurement().getTheoreticalStandardDeviation());
  329.     }

  330.     /** Finalize estimation.
  331.      * @param observedMeasurement measurement that has just been processed
  332.      * @param estimate corrected estimate
  333.      */
  334.     public void finalizeEstimation(final ObservedMeasurement<?> observedMeasurement,
  335.                                    final ProcessEstimate estimate) {
  336.         // Update the parameters with the estimated state
  337.         // The min/max values of the parameters are handled by the ParameterDriver implementation
  338.         setCorrectedEstimate(estimate);
  339.         updateParameters();

  340.         // Get the estimated propagator (mirroring parameter update in the builder)
  341.         // and the estimated spacecraft state
  342.         final Propagator[] estimatedPropagators = getEstimatedPropagators();
  343.         for (int k = 0; k < estimatedPropagators.length; ++k) {
  344.             setCorrectedSpacecraftState(estimatedPropagators[k].getInitialState(), k);
  345.         }

  346.         // Compute the estimated measurement using estimated spacecraft state
  347.         setCorrectedMeasurement(observedMeasurement.estimate(getCurrentMeasurementNumber(),
  348.                                                              getCurrentMeasurementNumber(),
  349.                                                              KalmanEstimatorUtil.filterRelevant(observedMeasurement, getCorrectedSpacecraftStates())));
  350.         // Update the trajectory
  351.         // ---------------------
  352.         updateReferenceTrajectories(estimatedPropagators);

  353.     }

  354.     /** Set the predicted normalized state vector.
  355.      * The predicted/propagated orbit is used to update the state vector
  356.      * @param date prediction date
  357.      * @return predicted state
  358.      */
  359.     private RealVector predictState(final AbsoluteDate date) {

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

  362.         // Orbital parameters counter
  363.         int jOrb = 0;

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

  365.             // Propagate the reference trajectory to measurement date
  366.             final SpacecraftState predictedSpacecraftState = referenceTrajectories[k].propagate(date);
  367.             setPredictedSpacecraftState(predictedSpacecraftState, k);

  368.             // Update the builder with the predicted orbit
  369.             // This updates the orbital drivers with the values of the predicted orbit
  370.             getBuilders().get(k).resetOrbit(predictedSpacecraftState.getOrbit());

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

  377.             // The orbital parameters in the state vector are replaced with their predicted values
  378.             // The propagation & measurement parameters are not changed by the prediction (i.e. the propagation)
  379.             // As the propagator builder was previously updated with the predicted orbit,
  380.             // the selected orbital drivers are already up to date with the prediction
  381.             for (DelegatingDriver orbitalDriver : getBuilders().get(k).getOrbitalParametersDrivers().getDrivers()) {
  382.                 if (orbitalDriver.isSelected()) {
  383.                     predictedState.setEntry(jOrb++, orbitalDriver.getNormalizedValue());
  384.                 }
  385.             }

  386.         }

  387.         return predictedState;

  388.     }

  389.     /** Update the estimated parameters after the correction phase of the filter.
  390.      * The min/max allowed values are handled by the parameter themselves.
  391.      */
  392.     private void updateParameters() {
  393.         final RealVector correctedState = getCorrectedEstimate().getState();
  394.         int i = 0;
  395.         for (final DelegatingDriver driver : getEstimatedOrbitalParameters().getDrivers()) {
  396.             // let the parameter handle min/max clipping
  397.             driver.setNormalizedValue(correctedState.getEntry(i));
  398.             correctedState.setEntry(i++, driver.getNormalizedValue());
  399.         }
  400.         for (final DelegatingDriver driver : getEstimatedPropagationParameters().getDrivers()) {
  401.             // let the parameter handle min/max clipping
  402.             driver.setNormalizedValue(correctedState.getEntry(i));
  403.             correctedState.setEntry(i++, driver.getNormalizedValue());
  404.         }
  405.         for (final DelegatingDriver driver : getEstimatedMeasurementsParameters().getDrivers()) {
  406.             // let the parameter handle min/max clipping
  407.             driver.setNormalizedValue(correctedState.getEntry(i));
  408.             correctedState.setEntry(i++, driver.getNormalizedValue());
  409.         }
  410.     }

  411.     /** Getter for the reference trajectories.
  412.      * @return the referencetrajectories
  413.      */
  414.     public Propagator[] getReferenceTrajectories() {
  415.         return referenceTrajectories.clone();
  416.     }

  417.     /** Setter for the reference trajectories.
  418.      * @param referenceTrajectories the reference trajectories to be setted
  419.      */
  420.     public void setReferenceTrajectories(final Propagator[] referenceTrajectories) {
  421.         this.referenceTrajectories = referenceTrajectories.clone();
  422.     }

  423. }