From d4d783021345ce16ec44d36ad825f1e110cd6e5c Mon Sep 17 00:00:00 2001 From: Guylaine Prat <guylaine.prat@c-s.fr> Date: Thu, 13 Dec 2018 15:04:11 +0100 Subject: [PATCH] Starting work on exception revamping. Fixes #373 --- .../rugged/adjustment/AdjustmentContext.java | 69 +++--- .../GroundOptimizationProblemBuilder.java | 93 ++++---- ...nterSensorsOptimizationProblemBuilder.java | 198 ++++++++---------- .../OptimizationProblemBuilder.java | 31 +-- .../java/org/orekit/rugged/api/Rugged.java | 91 +++----- .../org/orekit/rugged/api/RuggedBuilder.java | 44 ++-- .../java/org/orekit/rugged/errors/Dump.java | 106 ++++------ .../org/orekit/rugged/errors/DumpManager.java | 28 +-- .../orekit/rugged/errors/DumpReplayer.java | 61 ++---- .../orekit/rugged/errors/RuggedException.java | 2 +- .../orekit/rugged/errors/RuggedMessages.java | 3 +- .../intersection/BasicScanAlgorithm.java | 3 +- .../intersection/IgnoreDEMAlgorithm.java | 6 +- .../intersection/IntersectionAlgorithm.java | 4 +- .../duvenhage/DuvenhageAlgorithm.java | 27 +-- .../orekit/rugged/linesensor/LineSensor.java | 15 +- .../linesensor/SensorMeanPlaneCrossing.java | 31 +-- .../linesensor/SensorPixelCrossing.java | 14 +- .../org/orekit/rugged/raster/SimpleTile.java | 15 +- .../java/org/orekit/rugged/raster/Tile.java | 4 +- .../java/org/orekit/rugged/TestUtils.java | 27 +-- .../orekit/rugged/api/RuggedBuilderTest.java | 19 +- .../org/orekit/rugged/api/RuggedTest.java | 48 ++--- .../rugged/errors/DumpReplayerTest.java | 16 +- .../intersection/AbstractAlgorithmTest.java | 6 +- .../ConstantElevationAlgorithmTest.java | 4 +- .../duvenhage/DuvenhageAlgorithmTest.java | 15 +- .../duvenhage/MinMaxTreeTileTest.java | 20 +- .../rugged/linesensor/FixedRotationTest.java | 8 +- .../linesensor/PolynomialRotationTest.java | 8 +- .../SensorMeanPlaneCrossingTest.java | 30 +-- .../CheckedPatternElevationUpdater.java | 4 +- .../rugged/raster/CliffsElevationUpdater.java | 4 +- .../rugged/raster/RandomLandscapeUpdater.java | 3 +- .../orekit/rugged/raster/SimpleTileTest.java | 30 ++- .../orekit/rugged/raster/TilesCacheTest.java | 8 +- .../raster/VolcanicConeElevationUpdater.java | 5 +- .../refraction/AtmosphericRefractionTest.java | 2 +- .../refraction/MultiLayerModelTest.java | 20 +- .../rugged/utils/ExtendedEllipsoidTest.java | 28 +-- .../rugged/utils/GeodeticUtilities.java | 9 +- .../utils/RoughVisibilityEstimatorTest.java | 18 +- .../utils/SpacecraftToObservedBodyTest.java | 2 +- .../java/fr/cs/examples/DirectLocation.java | 4 +- .../fr/cs/examples/DirectLocationWithDEM.java | 8 +- .../java/fr/cs/examples/InverseLocation.java | 4 +- .../refiningPleiades/GroundRefining.java | 4 +- .../refiningPleiades/InterRefining.java | 4 +- .../examples/refiningPleiades/Refining.java | 38 ++-- .../GroundMeasurementGenerator.java | 12 +- .../generators/InterMeasurementGenerator.java | 24 +-- .../generators/Measurable.java | 11 +- .../metrics/LocalisationMetrics.java | 16 +- .../refiningPleiades/models/OrbitModel.java | 24 +-- .../models/PleiadesViewingModel.java | 15 +- 55 files changed, 517 insertions(+), 826 deletions(-) diff --git a/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java b/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java index ab131736..da495fe8 100644 --- a/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java +++ b/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java @@ -117,51 +117,40 @@ public class AdjustmentContext { * @param parametersConvergenceThreshold convergence threshold on normalized * parameters (dimensionless, related to parameters scales) * @return optimum of the least squares problem - * @exception RuggedException if several parameters with the same name - * exist, if no parameters have been selected for estimation, or - * if parameters cannot be estimated (too few measurements, - * ill-conditioned problem ...) */ public Optimum estimateFreeParameters(final Collection<String> ruggedNameList, final int maxEvaluations, - final double parametersConvergenceThreshold) - throws RuggedException { - - try { - - final List<Rugged> ruggedList = new ArrayList<Rugged>(); - final List<LineSensor> selectedSensors = new ArrayList<LineSensor>(); - for (String ruggedName : ruggedNameList) { - final Rugged rugged = this.viewingModel.get(ruggedName); - if (rugged == null) { - throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); - } - - ruggedList.add(rugged); - selectedSensors.addAll(rugged.getLineSensors()); + final double parametersConvergenceThreshold) { + + final List<Rugged> ruggedList = new ArrayList<Rugged>(); + final List<LineSensor> selectedSensors = new ArrayList<LineSensor>(); + for (String ruggedName : ruggedNameList) { + final Rugged rugged = this.viewingModel.get(ruggedName); + if (rugged == null) { + throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); } - final LeastSquareAdjuster adjuster = new LeastSquareAdjuster(this.optimizerID); - LeastSquaresProblem theProblem = null; - - // builder - switch (ruggedList.size()) { - case 1: - final Rugged rugged = ruggedList.get(0); - final GroundOptimizationProblemBuilder groundOptimizationProblem = new GroundOptimizationProblemBuilder(selectedSensors, measurements, rugged); - theProblem = groundOptimizationProblem.build(maxEvaluations, parametersConvergenceThreshold); - break; - case 2: - final InterSensorsOptimizationProblemBuilder interSensorsOptimizationProblem = new InterSensorsOptimizationProblemBuilder(selectedSensors, measurements, ruggedList); - theProblem = interSensorsOptimizationProblem.build(maxEvaluations, parametersConvergenceThreshold); - break; - default : - throw new RuggedException(RuggedMessages.UNSUPPORTED_REFINING_CONTEXT, ruggedList.size()); - } - - return adjuster.optimize(theProblem); + ruggedList.add(rugged); + selectedSensors.addAll(rugged.getLineSensors()); + } - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); + final LeastSquareAdjuster adjuster = new LeastSquareAdjuster(this.optimizerID); + LeastSquaresProblem theProblem = null; + + // builder + switch (ruggedList.size()) { + case 1: + final Rugged rugged = ruggedList.get(0); + final GroundOptimizationProblemBuilder groundOptimizationProblem = new GroundOptimizationProblemBuilder(selectedSensors, measurements, rugged); + theProblem = groundOptimizationProblem.build(maxEvaluations, parametersConvergenceThreshold); + break; + case 2: + final InterSensorsOptimizationProblemBuilder interSensorsOptimizationProblem = new InterSensorsOptimizationProblemBuilder(selectedSensors, measurements, ruggedList); + theProblem = interSensorsOptimizationProblem.build(maxEvaluations, parametersConvergenceThreshold); + break; + default : + throw new RuggedException(RuggedMessages.UNSUPPORTED_REFINING_CONTEXT, ruggedList.size()); } + + return adjuster.optimize(theProblem); } } diff --git a/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java b/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java index 566d791f..f816658f 100644 --- a/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java @@ -34,14 +34,14 @@ import org.hipparchus.optim.nonlinear.vector.leastsquares.ParameterValidator; import org.hipparchus.util.FastMath; import org.hipparchus.util.Pair; import org.orekit.bodies.GeodeticPoint; +import org.orekit.rugged.adjustment.measurements.Observables; +import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; import org.orekit.rugged.api.Rugged; import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.SensorPixel; -import org.orekit.rugged.adjustment.measurements.Observables; -import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; import org.orekit.utils.ParameterDriver; /** Ground optimization problem builder. @@ -80,20 +80,16 @@ public class GroundOptimizationProblemBuilder extends OptimizationProblemBuilder * @param sensors list of sensors to refine * @param measurements set of observables * @param rugged name of rugged to refine - * @throws RuggedException an exception is generated if no parameters has been selected for refining */ public GroundOptimizationProblemBuilder(final List<LineSensor> sensors, - final Observables measurements, final Rugged rugged) - throws RuggedException { + final Observables measurements, final Rugged rugged) { super(sensors, measurements); this.rugged = rugged; this.initMapping(); } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#initMapping() - */ + /** {@inheritDoc} */ @Override protected void initMapping() { @@ -107,60 +103,50 @@ public class GroundOptimizationProblemBuilder extends OptimizationProblemBuilder } } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#createTargetAndWeight() - */ + /** {@inheritDoc} */ @Override - protected void createTargetAndWeight() throws RuggedException { + protected void createTargetAndWeight() { - try { - int n = 0; - for (final SensorToGroundMapping reference : this.sensorToGroundMappings) { - n += reference.getMapping().size(); - } + int n = 0; + for (final SensorToGroundMapping reference : this.sensorToGroundMappings) { + n += reference.getMapping().size(); + } - if (n == 0) { - throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS); - } - final double[] target = new double[2 * n]; - final double[] weight = new double[2 * n]; - - double min = Double.POSITIVE_INFINITY; - double max = Double.NEGATIVE_INFINITY; - int k = 0; - - for (final SensorToGroundMapping reference : this.sensorToGroundMappings) { - for (final Map.Entry<SensorPixel, GeodeticPoint> mapping : reference.getMapping()) { - final SensorPixel sp = mapping.getKey(); - weight[k] = 1.0; - target[k++] = sp.getLineNumber(); - weight[k] = 1.0; - target[k++] = sp.getPixelNumber(); - min = FastMath.min(min, sp.getLineNumber()); - max = FastMath.max(max, sp.getLineNumber()); - } + if (n == 0) { + throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS); + } + final double[] target = new double[2 * n]; + final double[] weight = new double[2 * n]; + + double min = Double.POSITIVE_INFINITY; + double max = Double.NEGATIVE_INFINITY; + int k = 0; + + for (final SensorToGroundMapping reference : this.sensorToGroundMappings) { + for (final Map.Entry<SensorPixel, GeodeticPoint> mapping : reference.getMapping()) { + final SensorPixel sp = mapping.getKey(); + weight[k] = 1.0; + target[k++] = sp.getLineNumber(); + weight[k] = 1.0; + target[k++] = sp.getPixelNumber(); + min = FastMath.min(min, sp.getLineNumber()); + max = FastMath.max(max, sp.getLineNumber()); } - - this.minLine = (int) FastMath.floor(min - ESTIMATION_LINE_RANGE_MARGIN); - this.maxLine = (int) FastMath.ceil(max - ESTIMATION_LINE_RANGE_MARGIN); - this.targetAndWeight = new HashMap<String, double[]>(); - this.targetAndWeight.put(TARGET, target); - this.targetAndWeight.put(WEIGHT, weight); - - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); } + + this.minLine = (int) FastMath.floor(min - ESTIMATION_LINE_RANGE_MARGIN); + this.maxLine = (int) FastMath.ceil(max - ESTIMATION_LINE_RANGE_MARGIN); + this.targetAndWeight = new HashMap<String, double[]>(); + this.targetAndWeight.put(TARGET, target); + this.targetAndWeight.put(WEIGHT, weight); } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#createFunction() - */ + /** {@inheritDoc} */ @Override protected MultivariateJacobianFunction createFunction() { // model function final MultivariateJacobianFunction model = point -> { - try { // set the current parameters values int i = 0; @@ -215,10 +201,6 @@ public class GroundOptimizationProblemBuilder extends OptimizationProblemBuilder // inverse loc result with Jacobian for all reference points return new Pair<RealVector, RealMatrix>(value, jacobian); - - } catch (RuggedException re) { - throw new RuggedExceptionWrapper(re); - } }; return model; @@ -228,11 +210,10 @@ public class GroundOptimizationProblemBuilder extends OptimizationProblemBuilder /** Least square problem builder. * @param maxEvaluations maxIterations and evaluations * @param convergenceThreshold parameter convergence threshold - * @throws RuggedException if sensor is not found * @return the least square problem */ @Override - public final LeastSquaresProblem build(final int maxEvaluations, final double convergenceThreshold) throws RuggedException { + public final LeastSquaresProblem build(final int maxEvaluations, final double convergenceThreshold) { this.createTargetAndWeight(); final double[] target = this.targetAndWeight.get(TARGET); diff --git a/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java b/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java index 5da3c156..19a48a96 100644 --- a/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java @@ -35,14 +35,13 @@ import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresProblem; import org.hipparchus.optim.nonlinear.vector.leastsquares.MultivariateJacobianFunction; import org.hipparchus.optim.nonlinear.vector.leastsquares.ParameterValidator; import org.hipparchus.util.Pair; +import org.orekit.rugged.adjustment.measurements.Observables; +import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; import org.orekit.rugged.api.Rugged; import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.SensorPixel; -import org.orekit.rugged.adjustment.measurements.Observables; -import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; import org.orekit.rugged.utils.SpacecraftToObservedBody; import org.orekit.time.AbsoluteDate; import org.orekit.utils.ParameterDriver; @@ -75,11 +74,9 @@ public class InterSensorsOptimizationProblemBuilder extends OptimizationProblemB * @param sensors list of sensors to refine * @param measurements set of observables * @param ruggedList names of rugged to refine - * @throws RuggedException an exception is generated if no parameters has been selected for refining */ public InterSensorsOptimizationProblemBuilder(final List<LineSensor> sensors, - final Observables measurements, final Collection<Rugged> ruggedList) - throws RuggedException { + final Observables measurements, final Collection<Rugged> ruggedList) { super(sensors, measurements); this.ruggedMap = new LinkedHashMap<String, Rugged>(); @@ -89,9 +86,7 @@ public class InterSensorsOptimizationProblemBuilder extends OptimizationProblemB this.initMapping(); } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#initMapping() - */ + /** {@inheritDoc} */ @Override protected void initMapping() { @@ -116,143 +111,129 @@ public class InterSensorsOptimizationProblemBuilder extends OptimizationProblemB } } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#createTargetAndWeight() - */ + /** {@inheritDoc} */ @Override - protected void createTargetAndWeight() throws RuggedException { + protected void createTargetAndWeight() { - try { - int n = 0; - for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { - n += reference.getMapping().size(); - } - if (n == 0) { - throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS); - } + int n = 0; + for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { + n += reference.getMapping().size(); + } + if (n == 0) { + throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS); + } - n = 2 * n; + n = 2 * n; - final double[] target = new double[n]; - final double[] weight = new double[n]; + final double[] target = new double[n]; + final double[] weight = new double[n]; - int k = 0; - for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { + int k = 0; + for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { - // Get central body constraint weight - final double bodyConstraintWeight = reference.getBodyConstraintWeight(); + // Get central body constraint weight + final double bodyConstraintWeight = reference.getBodyConstraintWeight(); - int i = 0; - for (Iterator<Map.Entry<SensorPixel, SensorPixel>> gtIt = reference.getMapping().iterator(); gtIt.hasNext(); i++) { + int i = 0; + for (Iterator<Map.Entry<SensorPixel, SensorPixel>> gtIt = reference.getMapping().iterator(); gtIt.hasNext(); i++) { - if (i == reference.getMapping().size()) break; + if (i == reference.getMapping().size()) break; - // Get LOS distance - final Double losDistance = reference.getLosDistance(i); + // Get LOS distance + final Double losDistance = reference.getLosDistance(i); - weight[k] = 1.0 - bodyConstraintWeight; - target[k++] = losDistance.doubleValue(); + weight[k] = 1.0 - bodyConstraintWeight; + target[k++] = losDistance.doubleValue(); - // Get central body distance (constraint) - final Double bodyDistance = reference.getBodyDistance(i); - weight[k] = bodyConstraintWeight; - target[k++] = bodyDistance.doubleValue(); - } + // Get central body distance (constraint) + final Double bodyDistance = reference.getBodyDistance(i); + weight[k] = bodyConstraintWeight; + target[k++] = bodyDistance.doubleValue(); } - - this.targetAndWeight = new HashMap<String, double[]>(); - this.targetAndWeight.put(TARGET, target); - this.targetAndWeight.put(WEIGHT, weight); - - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); } + + this.targetAndWeight = new HashMap<String, double[]>(); + this.targetAndWeight.put(TARGET, target); + this.targetAndWeight.put(WEIGHT, weight); } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#createFunction() - */ + /** {@inheritDoc} */ @Override protected MultivariateJacobianFunction createFunction() { // model function final MultivariateJacobianFunction model = point -> { - try { - // set the current parameters values - int i = 0; - for (final ParameterDriver driver : this.getDrivers()) { - driver.setNormalizedValue(point.getEntry(i++)); - } - - final double[] target = this.targetAndWeight.get(TARGET); + // set the current parameters values + int i = 0; + for (final ParameterDriver driver : this.getDrivers()) { + driver.setNormalizedValue(point.getEntry(i++)); + } - // compute distance and its partial derivatives - final RealVector value = new ArrayRealVector(target.length); - final RealMatrix jacobian = new Array2DRowRealMatrix(target.length, this.getNbParams()); + final double[] target = this.targetAndWeight.get(TARGET); - int l = 0; - for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { + // compute distance and its partial derivatives + final RealVector value = new ArrayRealVector(target.length); + final RealMatrix jacobian = new Array2DRowRealMatrix(target.length, this.getNbParams()); - final String ruggedNameA = reference.getRuggedNameA(); - final String ruggedNameB = reference.getRuggedNameB(); - final Rugged ruggedA = this.ruggedMap.get(ruggedNameA); - if (ruggedA == null) { - throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); - } + int l = 0; + for (final SensorToSensorMapping reference : this.sensorToSensorMappings) { - final Rugged ruggedB = this.ruggedMap.get(ruggedNameB); - if (ruggedB == null) { - throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); - } + final String ruggedNameA = reference.getRuggedNameA(); + final String ruggedNameB = reference.getRuggedNameB(); + final Rugged ruggedA = this.ruggedMap.get(ruggedNameA); + if (ruggedA == null) { + throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); + } - for (final Map.Entry<SensorPixel, SensorPixel> mapping : reference.getMapping()) { + final Rugged ruggedB = this.ruggedMap.get(ruggedNameB); + if (ruggedB == null) { + throw new RuggedException(RuggedMessages.INVALID_RUGGED_NAME); + } - final SensorPixel spA = mapping.getKey(); - final SensorPixel spB = mapping.getValue(); + for (final Map.Entry<SensorPixel, SensorPixel> mapping : reference.getMapping()) { - final LineSensor lineSensorB = ruggedB.getLineSensor(reference.getSensorNameB()); - final LineSensor lineSensorA = ruggedA.getLineSensor(reference.getSensorNameA()); + final SensorPixel spA = mapping.getKey(); + final SensorPixel spB = mapping.getValue(); - final AbsoluteDate dateA = lineSensorA.getDate(spA.getLineNumber()); - final AbsoluteDate dateB = lineSensorB.getDate(spB.getLineNumber()); + final LineSensor lineSensorB = ruggedB.getLineSensor(reference.getSensorNameB()); + final LineSensor lineSensorA = ruggedA.getLineSensor(reference.getSensorNameA()); - final double pixelA = spA.getPixelNumber(); - final double pixelB = spB.getPixelNumber(); + final AbsoluteDate dateA = lineSensorA.getDate(spA.getLineNumber()); + final AbsoluteDate dateB = lineSensorB.getDate(spB.getLineNumber()); - final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody(); + final double pixelA = spA.getPixelNumber(); + final double pixelB = spB.getPixelNumber(); - final DerivativeStructure[] ilResult = - ruggedB.distanceBetweenLOSderivatives(lineSensorA, dateA, pixelA, scToBodyA, - lineSensorB, dateB, pixelB, this.getGenerator()); + final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody(); - // extract the value - value.setEntry(l, ilResult[0].getValue()); - value.setEntry(l + 1, ilResult[1].getValue()); + final DerivativeStructure[] ilResult = + ruggedB.distanceBetweenLOSderivatives(lineSensorA, dateA, pixelA, scToBodyA, + lineSensorB, dateB, pixelB, this.getGenerator()); - // extract the Jacobian - final int[] orders = new int[this.getNbParams()]; - int m = 0; + // extract the value + value.setEntry(l, ilResult[0].getValue()); + value.setEntry(l + 1, ilResult[1].getValue()); - for (final ParameterDriver driver : this.getDrivers()) { - final double scale = driver.getScale(); - orders[m] = 1; - jacobian.setEntry(l, m, ilResult[0].getPartialDerivative(orders) * scale); - jacobian.setEntry(l + 1, m, ilResult[1].getPartialDerivative(orders) * scale); - orders[m] = 0; - m++; - } + // extract the Jacobian + final int[] orders = new int[this.getNbParams()]; + int m = 0; - l += 2; // pass to the next evaluation + for (final ParameterDriver driver : this.getDrivers()) { + final double scale = driver.getScale(); + orders[m] = 1; + jacobian.setEntry(l, m, ilResult[0].getPartialDerivative(orders) * scale); + jacobian.setEntry(l + 1, m, ilResult[1].getPartialDerivative(orders) * scale); + orders[m] = 0; + m++; } - } - // distance result with Jacobian for all reference points - return new Pair<RealVector, RealMatrix>(value, jacobian); - - } catch (RuggedException re) { - throw new RuggedExceptionWrapper(re); + l += 2; // pass to the next evaluation + } } + + // distance result with Jacobian for all reference points + return new Pair<RealVector, RealMatrix>(value, jacobian); }; return model; @@ -262,11 +243,10 @@ public class InterSensorsOptimizationProblemBuilder extends OptimizationProblemB /** Least square problem builder. * @param maxEvaluations maxIterations and evaluations * @param convergenceThreshold parameter convergence threshold - * @throws RuggedException if sensor is not found * @return the least square problem */ @Override - public final LeastSquaresProblem build(final int maxEvaluations, final double convergenceThreshold) throws RuggedException { + public final LeastSquaresProblem build(final int maxEvaluations, final double convergenceThreshold) { this.createTargetAndWeight(); final double[] target = this.targetAndWeight.get(TARGET); diff --git a/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java b/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java index 954cc914..3272a098 100644 --- a/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java @@ -32,7 +32,6 @@ import org.hipparchus.optim.nonlinear.vector.leastsquares.MultivariateJacobianFu import org.hipparchus.optim.nonlinear.vector.leastsquares.ParameterValidator; import org.orekit.rugged.adjustment.measurements.Observables; import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.utils.DSGenerator; @@ -70,21 +69,15 @@ abstract class OptimizationProblemBuilder { /** Constructor. * @param sensors list of sensors to refine * @param measurements set of observables - * @throws RuggedException an exception is generated if no parameters has been selected for refining */ - OptimizationProblemBuilder(final List<LineSensor> sensors, final Observables measurements) throws RuggedException { - - try { - this.generator = this.createGenerator(sensors); - this.drivers = this.generator.getSelected(); - this.nbParams = this.drivers.size(); - if (this.nbParams == 0) { - throw new RuggedException(RuggedMessages.NO_PARAMETERS_SELECTED); - } - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); - } + OptimizationProblemBuilder(final List<LineSensor> sensors, final Observables measurements) { + this.generator = this.createGenerator(sensors); + this.drivers = this.generator.getSelected(); + this.nbParams = this.drivers.size(); + if (this.nbParams == 0) { + throw new RuggedException(RuggedMessages.NO_PARAMETERS_SELECTED); + } this.measurements = measurements; this.sensors = sensors; } @@ -92,12 +85,10 @@ abstract class OptimizationProblemBuilder { /** Least squares problem builder. * @param maxEvaluations maximum number of evaluations * @param convergenceThreshold convergence threshold - * @throws RuggedException if sensor is not found * @return the least squares problem */ - public abstract LeastSquaresProblem build(int maxEvaluations, double convergenceThreshold) - throws RuggedException; + public abstract LeastSquaresProblem build(int maxEvaluations, double convergenceThreshold); /** Create the convergence check. * <p> @@ -129,10 +120,8 @@ abstract class OptimizationProblemBuilder { return start; } - /** Create targets and weights of optimization problem. - * @throws RuggedException if no reference mappings for parameters estimation are found - */ - protected abstract void createTargetAndWeight() throws RuggedException; + /** Create targets and weights of optimization problem. */ + protected abstract void createTargetAndWeight(); /** Create the model function value and its Jacobian. * @return the model function value and its Jacobian diff --git a/src/main/java/org/orekit/rugged/api/Rugged.java b/src/main/java/org/orekit/rugged/api/Rugged.java index c3b26db7..e0bd10cb 100644 --- a/src/main/java/org/orekit/rugged/api/Rugged.java +++ b/src/main/java/org/orekit/rugged/api/Rugged.java @@ -238,10 +238,8 @@ public class Rugged { * @param sensorName name of the line sensor * @param lineNumber number of the line to localize on ground * @return ground position of all pixels of the specified sensor line - * @exception RuggedException if line cannot be localized, or sensor is unknown */ - public GeodeticPoint[] directLocation(final String sensorName, final double lineNumber) - throws RuggedException { + public GeodeticPoint[] directLocation(final String sensorName, final double lineNumber) { final LineSensor sensor = getLineSensor(sensorName); final Vector3D sensorPosition = sensor.getPosition(); @@ -323,10 +321,8 @@ public class Rugged { * we consider each pixel to be at sensor position * @param los normalized line-of-sight in spacecraft frame * @return ground position of intersection point between specified los and ground - * @exception RuggedException if line cannot be localized, sensor is unknown or problem with atmospheric data */ - public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los) - throws RuggedException { + public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los) { // Set the pixel to null in order not to compute atmosphere with optimization final PixelLOS pixelLOS = new PixelLOS(null, los); @@ -344,10 +340,8 @@ public class Rugged { * we consider each pixel to be at sensor position * @param pixelLOS pixel definition with normalized line-of-sight in spacecraft frame * @return ground position of intersection point between specified los and ground - * @exception RuggedException if line cannot be localized, sensor is unknown or problem with atmospheric data */ - public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D sensorPosition, final PixelLOS pixelLOS) - throws RuggedException { + public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D sensorPosition, final PixelLOS pixelLOS) { final Vector3D los = pixelLOS.getLOS(); // TODO change dump to add sensorPixel @@ -449,14 +443,13 @@ public class Rugged { * @param minLine minimum line number * @param maxLine maximum line number * @return date at which ground point is seen by line sensor - * @exception RuggedException if line cannot be localized, or sensor is unknown * @see #inverseLocation(String, double, double, int, int) * @see org.orekit.rugged.utils.RoughVisibilityEstimator */ public AbsoluteDate dateLocation(final String sensorName, final double latitude, final double longitude, - final int minLine, final int maxLine) - throws RuggedException { + final int minLine, final int maxLine) { + final GeodeticPoint groundPoint = new GeodeticPoint(latitude, longitude, algorithm.getElevation(latitude, longitude)); return dateLocation(sensorName, groundPoint, minLine, maxLine); @@ -485,13 +478,11 @@ public class Rugged { * @param minLine minimum line number * @param maxLine maximum line number * @return date at which ground point is seen by line sensor - * @exception RuggedException if line cannot be localized, or sensor is unknown * @see #inverseLocation(String, GeodeticPoint, int, int) * @see org.orekit.rugged.utils.RoughVisibilityEstimator */ public AbsoluteDate dateLocation(final String sensorName, final GeodeticPoint point, - final int minLine, final int maxLine) - throws RuggedException { + final int minLine, final int maxLine) { final LineSensor sensor = getLineSensor(sensorName); final SensorMeanPlaneCrossing planeCrossing = getPlaneCrossing(sensorName, minLine, maxLine); @@ -532,13 +523,12 @@ public class Rugged { * @param maxLine maximum line number * @return sensor pixel seeing ground point, or null if ground point cannot * be seen between the prescribed line numbers - * @exception RuggedException if line cannot be localized, or sensor is unknown * @see org.orekit.rugged.utils.RoughVisibilityEstimator */ public SensorPixel inverseLocation(final String sensorName, final double latitude, final double longitude, - final int minLine, final int maxLine) - throws RuggedException { + final int minLine, final int maxLine) { + final GeodeticPoint groundPoint = new GeodeticPoint(latitude, longitude, algorithm.getElevation(latitude, longitude)); return inverseLocation(sensorName, groundPoint, minLine, maxLine); } @@ -563,13 +553,11 @@ public class Rugged { * @param maxLine maximum line number where the search will be performed * @return sensor pixel seeing point, or null if point cannot be seen between the * prescribed line numbers - * @exception RuggedException if line cannot be localized, or sensor is unknown * @see #dateLocation(String, GeodeticPoint, int, int) * @see org.orekit.rugged.utils.RoughVisibilityEstimator */ public SensorPixel inverseLocation(final String sensorName, final GeodeticPoint point, - final int minLine, final int maxLine) - throws RuggedException { + final int minLine, final int maxLine) { final LineSensor sensor = getLineSensor(sensorName); DumpManager.dumpInverseLocation(sensor, point, minLine, maxLine, lightTimeCorrection, aberrationOfLightCorrection); @@ -620,13 +608,11 @@ public class Rugged { * @param pInert sensor position in inertial frame * @param lInert line of sight in inertial frame * @return geodetic point with light time correction - * @throws RuggedException if intersection cannot be found */ private NormalizedGeodeticPoint computeWithLightTimeCorrection(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los, final Transform scToInert, final Transform inertToBody, - final Vector3D pInert, final Vector3D lInert) - throws RuggedException { + final Vector3D pInert, final Vector3D lInert) { // compute the approximate transform between spacecraft and observed body final Transform approximate = new Transform(date, scToInert, inertToBody); @@ -656,12 +642,10 @@ public class Rugged { * @param sensor the line sensor * @param planeCrossing the sensor mean plane crossing * @return the sensor pixel crossing or null if cannot be found - * @throws RuggedException if sensor cannot be found * @since 3.0 */ private SensorPixel findSensorPixelWithoutAtmosphere(final GeodeticPoint point, - final LineSensor sensor, final SensorMeanPlaneCrossing planeCrossing) - throws RuggedException { + final LineSensor sensor, final SensorMeanPlaneCrossing planeCrossing) { // find approximately the sensor line at which ground point crosses sensor mean plane final Vector3D target = ellipsoid.transform(point); @@ -722,12 +706,10 @@ public class Rugged { * @param minLine minimum line number where the search will be performed * @param maxLine maximum line number where the search will be performed * @return the sensor pixel crossing or null if cannot be found - * @throws RuggedException if problem while computing correction * @since 3.0 */ private SensorPixel findSensorPixelWithAtmosphere(final GeodeticPoint point, - final LineSensor sensor, final int minLine, final int maxLine) - throws RuggedException { + final LineSensor sensor, final int minLine, final int maxLine) { // TBN: there is no direct way to compute the inverse location. // The method is based on an interpolation grid associated with the fixed point method @@ -820,12 +802,10 @@ public class Rugged { * @param minLine minimum line number where the search will be performed * @param maxLine maximum line number where the search will be performed * @return the sensor pixel grid computed without atmosphere - * @throws RuggedException if invalid range for lines */ private SensorPixel[][] computeInverseLocOnGridWithoutAtmosphere(final GeodeticPoint[][] groundGridWithAtmosphere, final int nbPixelGrid, final int nbLineGrid, - final LineSensor sensor, final int minLine, final int maxLine) - throws RuggedException { + final LineSensor sensor, final int minLine, final int maxLine) { final SensorPixel[][] sensorPixelGrid = new SensorPixel[nbPixelGrid][nbLineGrid]; final String sensorName = sensor.getName(); @@ -850,8 +830,8 @@ public class Rugged { } else if (sensorPixelGrid[uIndex][vIndex] == null) { throw new RuggedException(RuggedMessages.INVALID_RANGE_FOR_LINES, minLine, maxLine, ""); } - } catch (RuggedException re) { - throw new RuggedException(RuggedMessages.INVALID_RANGE_FOR_LINES, minLine, maxLine, ""); + } catch (RuggedException re) { // This should never happen + throw RuggedException.createInternalError(re); } } else { // groundGrid[uIndex][vIndex] == null: impossible to compute inverse loc because ground point not defined @@ -868,10 +848,9 @@ public class Rugged { * @param lineGrid the line grid * @param sensor the line sensor * @return the ground grid computed with atmosphere - * @throws RuggedException if a problem occurs while computing direct location on sensor grid with atmospheric refraction */ - private GeodeticPoint[][] computeDirectLocOnGridWithAtmosphere(final double[] pixelGrid, final double[] lineGrid, final LineSensor sensor) - throws RuggedException { + private GeodeticPoint[][] computeDirectLocOnGridWithAtmosphere(final double[] pixelGrid, final double[] lineGrid, + final LineSensor sensor) { final int nbPixelGrid = pixelGrid.length; final int nbLineGrid = lineGrid.length; @@ -887,7 +866,7 @@ public class Rugged { try { groundGridWithAtmosphere[uIndex][vIndex] = directLocation(date, sensorPosition, los); } catch (RuggedException re) { // This should never happen - throw new RuggedException(RuggedMessages.INTERNAL_ERROR, re); + throw RuggedException.createInternalError(re); } } // end loop vIndex } // end loop uIndex @@ -903,13 +882,11 @@ public class Rugged { * @param dateB current date for sensor B * @param pixelB pixel index for sensor B * @return distances computed between LOS and to the ground - * @exception RuggedException if frames cannot be computed at date or if date cannot be handled * @since 2.0 */ public double[] distanceBetweenLOS(final LineSensor sensorA, final AbsoluteDate dateA, final double pixelA, final SpacecraftToObservedBody scToBodyA, - final LineSensor sensorB, final AbsoluteDate dateB, final double pixelB) - throws RuggedException { + final LineSensor sensorB, final AbsoluteDate dateB, final double pixelB) { // Compute the approximate transform between spacecraft and observed body // from Rugged instance A @@ -976,15 +953,13 @@ public class Rugged { * @param pixelB pixel index for sensor B * @param generator generator to use for building {@link DerivativeStructure} instances * @return distances computed, with derivatives, between LOS and to the ground - * @exception RuggedException if frames cannot be computed at date * @see #distanceBetweenLOS(LineSensor, AbsoluteDate, double, SpacecraftToObservedBody, LineSensor, AbsoluteDate, double) */ public DerivativeStructure[] distanceBetweenLOSderivatives( final LineSensor sensorA, final AbsoluteDate dateA, final double pixelA, final SpacecraftToObservedBody scToBodyA, final LineSensor sensorB, final AbsoluteDate dateB, final double pixelB, - final DSGenerator generator) - throws RuggedException { + final DSGenerator generator) { // Compute the approximate transforms between spacecraft and observed body // from Rugged instance A @@ -1059,11 +1034,9 @@ public class Rugged { * @param minLine minimum line number * @param maxLine maximum line number * @return mean plane crossing finder - * @exception RuggedException if sensor is unknown */ private SensorMeanPlaneCrossing getPlaneCrossing(final String sensorName, - final int minLine, final int maxLine) - throws RuggedException { + final int minLine, final int maxLine) { final LineSensor sensor = getLineSensor(sensorName); SensorMeanPlaneCrossing planeCrossing = finders.get(sensorName); @@ -1087,10 +1060,8 @@ public class Rugged { /** Set the mean plane crossing finder for a sensor. * @param planeCrossing plane crossing finder - * @exception RuggedException if sensor is unknown */ - private void setPlaneCrossing(final SensorMeanPlaneCrossing planeCrossing) - throws RuggedException { + private void setPlaneCrossing(final SensorMeanPlaneCrossing planeCrossing) { finders.put(planeCrossing.getSensor().getName(), planeCrossing); } @@ -1102,7 +1073,6 @@ public class Rugged { * @param generator generator to use for building {@link DerivativeStructure} instances * @return sensor pixel seeing point with derivatives, or null if point cannot be seen between the * prescribed line numbers - * @exception RuggedException if line cannot be localized, or sensor is unknown * @see #inverseLocation(String, GeodeticPoint, int, int) * @since 2.0 */ @@ -1111,8 +1081,7 @@ public class Rugged { final GeodeticPoint point, final int minLine, final int maxLine, - final DSGenerator generator) - throws RuggedException { + final DSGenerator generator) { final LineSensor sensor = getLineSensor(sensorName); @@ -1176,30 +1145,24 @@ public class Rugged { /** Get transform from spacecraft to inertial frame. * @param date date of the transform * @return transform from spacecraft to inertial frame - * @exception RuggedException if spacecraft position or attitude cannot be computed at date */ - public Transform getScToInertial(final AbsoluteDate date) - throws RuggedException { + public Transform getScToInertial(final AbsoluteDate date) { return scToBody.getScToInertial(date); } /** Get transform from inertial frame to observed body frame. * @param date date of the transform * @return transform from inertial frame to observed body frame - * @exception RuggedException if frames cannot be computed at date */ - public Transform getInertialToBody(final AbsoluteDate date) - throws RuggedException { + public Transform getInertialToBody(final AbsoluteDate date) { return scToBody.getInertialToBody(date); } /** Get transform from observed body frame to inertial frame. * @param date date of the transform * @return transform from observed body frame to inertial frame - * @exception RuggedException if frames cannot be computed at date */ - public Transform getBodyToInertial(final AbsoluteDate date) - throws RuggedException { + public Transform getBodyToInertial(final AbsoluteDate date) { return scToBody.getBodyToInertial(date); } @@ -1208,7 +1171,7 @@ public class Rugged { * @return selected sensor * @exception RuggedException if sensor is not known */ - public LineSensor getLineSensor(final String sensorName) throws RuggedException { + public LineSensor getLineSensor(final String sensorName) { final LineSensor sensor = sensors.get(sensorName); if (sensor == null) { throw new RuggedException(RuggedMessages.UNKNOWN_SENSOR, sensorName); diff --git a/src/main/java/org/orekit/rugged/api/RuggedBuilder.java b/src/main/java/org/orekit/rugged/api/RuggedBuilder.java index 392e19a0..e1351a3a 100644 --- a/src/main/java/org/orekit/rugged/api/RuggedBuilder.java +++ b/src/main/java/org/orekit/rugged/api/RuggedBuilder.java @@ -183,28 +183,22 @@ public class RuggedBuilder { /** Set the reference ellipsoid. * @param ellipsoidID reference ellipsoid * @param bodyRotatingFrameID body rotating frame identifier - * @exception RuggedException if data needed for some frame cannot be loaded - * or if trajectory has been {@link #setTrajectoryAndTimeSpan(InputStream) recovered} * from an earlier run and frames mismatch * @return the builder instance * @see #setEllipsoid(OneAxisEllipsoid) * @see #getEllipsoid() */ - public RuggedBuilder setEllipsoid(final EllipsoidId ellipsoidID, final BodyRotatingFrameId bodyRotatingFrameID) - throws RuggedException { + public RuggedBuilder setEllipsoid(final EllipsoidId ellipsoidID, final BodyRotatingFrameId bodyRotatingFrameID) { return setEllipsoid(selectEllipsoid(ellipsoidID, selectBodyRotatingFrame(bodyRotatingFrameID))); } /** Set the reference ellipsoid. * @param newEllipsoid reference ellipsoid * @return the builder instance - * @exception RuggedException if trajectory has been - * {@link #setTrajectoryAndTimeSpan(InputStream) recovered} from an earlier run and frames mismatch * @see #setEllipsoid(EllipsoidId, BodyRotatingFrameId) * @see #getEllipsoid() */ - public RuggedBuilder setEllipsoid(final OneAxisEllipsoid newEllipsoid) - throws RuggedException { + public RuggedBuilder setEllipsoid(final OneAxisEllipsoid newEllipsoid) { this.ellipsoid = new ExtendedEllipsoid(newEllipsoid.getEquatorialRadius(), newEllipsoid.getFlattening(), newEllipsoid.getBodyFrame()); @@ -415,7 +409,6 @@ public class RuggedBuilder { * @param aInterpolationNumber number of points to use for attitude interpolation * @param aFilter filter for derivatives from the sample to use in attitude interpolation * @return the builder instance - * @exception RuggedException if data needed for inertial frame cannot be loaded * @see #setTrajectory(Frame, List, int, CartesianDerivativesFilter, List, int, AngularDerivativesFilter) * @see #setTrajectory(double, int, CartesianDerivativesFilter, AngularDerivativesFilter, Propagator) * @see #setTrajectoryAndTimeSpan(InputStream) @@ -431,8 +424,8 @@ public class RuggedBuilder { final List<TimeStampedPVCoordinates> positionsVelocities, final int pvInterpolationNumber, final CartesianDerivativesFilter pvFilter, final List<TimeStampedAngularCoordinates> quaternions, final int aInterpolationNumber, - final AngularDerivativesFilter aFilter) - throws RuggedException { + final AngularDerivativesFilter aFilter) { + return setTrajectory(selectInertialFrame(inertialFrameId), positionsVelocities, pvInterpolationNumber, pvFilter, quaternions, aInterpolationNumber, aFilter); @@ -467,6 +460,7 @@ public class RuggedBuilder { final CartesianDerivativesFilter pvFilter, final List<TimeStampedAngularCoordinates> quaternions, final int aInterpolationNumber, final AngularDerivativesFilter aFilter) { + this.inertial = inertialFrame; this.pvSample = positionsVelocities; this.pvNeighborsSize = pvInterpolationNumber; @@ -588,8 +582,8 @@ public class RuggedBuilder { * @see #setTrajectory(double, int, CartesianDerivativesFilter, AngularDerivativesFilter, Propagator) * @see #storeInterpolator(OutputStream) */ - public RuggedBuilder setTrajectoryAndTimeSpan(final InputStream storageStream) - throws RuggedException { + public RuggedBuilder setTrajectoryAndTimeSpan(final InputStream storageStream) { + try { this.inertial = null; this.pvSample = null; @@ -608,6 +602,7 @@ public class RuggedBuilder { this.overshootTolerance = scToBody.getOvershootTolerance(); checkFramesConsistency(); return this; + } catch (ClassNotFoundException cnfe) { throw new RuggedException(cnfe, RuggedMessages.NOT_INTERPOLATOR_DUMP_DATA); } catch (ClassCastException cce) { @@ -638,7 +633,7 @@ public class RuggedBuilder { * @see #setTrajectory(double, int, CartesianDerivativesFilter, AngularDerivativesFilter, Propagator) * @see #setTrajectoryAndTimeSpan(InputStream) */ - public void storeInterpolator(final OutputStream storageStream) throws RuggedException { + public void storeInterpolator(final OutputStream storageStream) { try { createInterpolatorIfNeeded(); new ObjectOutputStream(storageStream).writeObject(scToBody); @@ -651,7 +646,7 @@ public class RuggedBuilder { * @exception RuggedException if frames have been set both by direct calls and by * deserializing an interpolator dump and a mismatch occurs */ - private void checkFramesConsistency() throws RuggedException { + private void checkFramesConsistency() { if (ellipsoid != null && scToBody != null && !ellipsoid.getBodyFrame().getName().equals(scToBody.getBodyFrame().getName())) { throw new RuggedException(RuggedMessages.FRAMES_MISMATCH_WITH_INTERPOLATOR_DUMP, @@ -664,7 +659,7 @@ public class RuggedBuilder { * or attitude samples do not fully cover the [{@code minDate}, {@code maxDate}] search time span, * or propagator fails. */ - private void createInterpolatorIfNeeded() throws RuggedException { + private void createInterpolatorIfNeeded() { if (ellipsoid == null) { throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setEllipsoid()"); @@ -684,7 +679,6 @@ public class RuggedBuilder { throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setTrajectory()"); } } - } /** Create a transform interpolator from positions and quaternions lists. @@ -701,8 +695,6 @@ public class RuggedBuilder { * @param aInterpolationNumber number of points to use for attitude interpolation * @param aFilter filter for derivatives from the sample to use in attitude interpolation * @return transforms interpolator - * @exception RuggedException if data needed for some frame cannot be loaded or if position - * or attitude samples do not fully cover the [{@code minDate}, {@code maxDate}] search time span */ private static SpacecraftToObservedBody createInterpolator(final Frame inertialFrame, final Frame bodyFrame, final AbsoluteDate minDate, final AbsoluteDate maxDate, @@ -712,8 +704,8 @@ public class RuggedBuilder { final CartesianDerivativesFilter pvFilter, final List<TimeStampedAngularCoordinates> quaternions, final int aInterpolationNumber, - final AngularDerivativesFilter aFilter) - throws RuggedException { + final AngularDerivativesFilter aFilter) { + return new SpacecraftToObservedBody(inertialFrame, bodyFrame, minDate, maxDate, tStep, overshootTolerance, positionsVelocities, pvInterpolationNumber, @@ -734,7 +726,6 @@ public class RuggedBuilder { * @param aFilter filter for derivatives from the sample to use in attitude interpolation * @param propagator global propagator * @return transforms interpolator - * @exception RuggedException if data needed for some frame cannot be loaded */ private static SpacecraftToObservedBody createInterpolator(final Frame inertialFrame, final Frame bodyFrame, final AbsoluteDate minDate, final AbsoluteDate maxDate, @@ -753,8 +744,7 @@ public class RuggedBuilder { /** {@inheritDoc} */ @Override - public void handleStep(final SpacecraftState currentState, final boolean isLast) - throws OrekitException { + public void handleStep(final SpacecraftState currentState, final boolean isLast) { final AbsoluteDate date = currentState.getDate(); final PVCoordinates pv = currentState.getPVCoordinates(inertialFrame); final Rotation q = currentState.getAttitude().getRotation(); @@ -771,7 +761,6 @@ public class RuggedBuilder { positionsVelocities, interpolationNumber, pvFilter, quaternions, interpolationNumber, aFilter); - } /** Set flag for light time correction. @@ -986,7 +975,8 @@ public class RuggedBuilder { * @exception RuggedException if the builder is not properly configured * or if some internal elements cannot be built (frames, ephemerides, ...) */ - public Rugged build() throws RuggedException { + public Rugged build() { + if (algorithmID == null) { throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setAlgorithmID()"); } @@ -1002,7 +992,5 @@ public class RuggedBuilder { createInterpolatorIfNeeded(); return new Rugged(createAlgorithm(algorithmID, tileUpdater, maxCachedTiles, constantElevation), ellipsoid, lightTimeCorrection, aberrationOfLightCorrection, atmosphericRefraction, scToBody, sensors, name); - } - } diff --git a/src/main/java/org/orekit/rugged/errors/Dump.java b/src/main/java/org/orekit/rugged/errors/Dump.java index 9572ca90..6420fa25 100644 --- a/src/main/java/org/orekit/rugged/errors/Dump.java +++ b/src/main/java/org/orekit/rugged/errors/Dump.java @@ -31,7 +31,6 @@ import org.hipparchus.util.FastMath; import org.hipparchus.util.OpenIntToDoubleHashMap; import org.hipparchus.util.Pair; import org.orekit.bodies.GeodeticPoint; -import org.orekit.errors.OrekitException; import org.orekit.frames.FactoryManagedFrame; import org.orekit.frames.Frame; import org.orekit.frames.Transform; @@ -150,12 +149,10 @@ class Dump { * @param lightTimeCorrection flag for light time correction * @param aberrationOfLightCorrection flag for aberration of light correction * @param refractionCorrection flag for refraction correction - * @exception RuggedException if date cannot be converted to UTC */ public void dumpDirectLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los, final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection, - final boolean refractionCorrection) - throws RuggedException { + final boolean refractionCorrection) { writer.format(Locale.US, "direct location: date %s position %22.15e %22.15e %22.15e los %22.15e %22.15e %22.15e lightTime %b aberration %b refraction %b %n", convertDate(date), @@ -166,10 +163,8 @@ class Dump { /** Dump a direct location result. * @param gp resulting geodetic point - * @exception RuggedException if date cannot be converted to UTC */ - public void dumpDirectLocationResult(final GeodeticPoint gp) - throws RuggedException { + public void dumpDirectLocationResult(final GeodeticPoint gp) { if (gp != null) { writer.format(Locale.US, "direct location result: latitude %22.15e longitude %22.15e elevation %22.15e%n", @@ -213,11 +208,9 @@ class Dump { * @param index index of the transform * @param bodyToInertial transform from body frame to inertial frame * @param scToInertial transfrom from spacecraft frame to inertial frame - * @exception RuggedException if reference date cannot be converted to UTC */ public void dumpTransform(final SpacecraftToObservedBody scToBody, final int index, - final Transform bodyToInertial, final Transform scToInertial) - throws RuggedException { + final Transform bodyToInertial, final Transform scToInertial) { if (tranformsDumped == null) { final AbsoluteDate minDate = scToBody.getMinDate(); final AbsoluteDate maxDate = scToBody.getMaxDate(); @@ -243,10 +236,8 @@ class Dump { /** Dump a sensor mean plane. * @param meanPlane mean plane associated with sensor - * @exception RuggedException if some frames cannot be computed at mid date */ - public void dumpSensorMeanPlane(final SensorMeanPlaneCrossing meanPlane) - throws RuggedException { + public void dumpSensorMeanPlane(final SensorMeanPlaneCrossing meanPlane){ getSensorData(meanPlane.getSensor()).setMeanPlane(meanPlane); } @@ -255,10 +246,8 @@ class Dump { * @param date date * @param i pixel index * @param los pixel normalized line-of-sight - * @exception RuggedException if date cannot be converted to UTC */ - public void dumpSensorLOS(final LineSensor sensor, final AbsoluteDate date, final int i, final Vector3D los) - throws RuggedException { + public void dumpSensorLOS(final LineSensor sensor, final AbsoluteDate date, final int i, final Vector3D los) { getSensorData(sensor).setLOS(date, i, los); } @@ -266,10 +255,8 @@ class Dump { * @param sensor sensor * @param lineNumber line number * @param date date - * @exception RuggedException if date cannot be converted to UTC */ - public void dumpSensorDatation(final LineSensor sensor, final double lineNumber, final AbsoluteDate date) - throws RuggedException { + public void dumpSensorDatation(final LineSensor sensor, final double lineNumber, final AbsoluteDate date) { getSensorData(sensor).setDatation(lineNumber, date); } @@ -492,46 +479,41 @@ class Dump { /** Set the mean plane finder. * @param meanPlane mean plane finder - * @exception RuggedException if frames cannot be computed at mid date */ - public void setMeanPlane(final SensorMeanPlaneCrossing meanPlane) throws RuggedException { - try { - if (this.meanPlane == null) { - this.meanPlane = meanPlane; - final long nbResults = meanPlane.getCachedResults().count(); - writer.format(Locale.US, - "sensor mean plane: sensorName %s minLine %d maxLine %d maxEval %d accuracy %22.15e normal %22.15e %22.15e %22.15e cachedResults %d", - dumpName, - meanPlane.getMinLine(), meanPlane.getMaxLine(), - meanPlane.getMaxEval(), meanPlane.getAccuracy(), - meanPlane.getMeanPlaneNormal().getX(), meanPlane.getMeanPlaneNormal().getY(), meanPlane.getMeanPlaneNormal().getZ(), - nbResults); - meanPlane.getCachedResults().forEach(result -> { - try { - writer.format(Locale.US, - " lineNumber %22.15e date %s target %22.15e %22.15e %22.15e targetDirection %22.15e %22.15e %22.15e %22.15e %22.15e %22.15e", - result.getLine(), convertDate(result.getDate()), - result.getTarget().getX(), result.getTarget().getY(), result.getTarget().getZ(), - result.getTargetDirection().getX(), - result.getTargetDirection().getY(), - result.getTargetDirection().getZ(), - result.getTargetDirectionDerivative().getZ(), - result.getTargetDirectionDerivative().getY(), - result.getTargetDirectionDerivative().getZ()); - } catch (RuggedException re) { - throw new RuggedExceptionWrapper(re); - } - }); - writer.format(Locale.US, "%n"); - - // ensure the transforms for mid date are dumped - final AbsoluteDate midDate = meanPlane.getSensor().getDate(0.5 * (meanPlane.getMinLine() + meanPlane.getMaxLine())); - meanPlane.getScToBody().getBodyToInertial(midDate); - meanPlane.getScToBody().getScToInertial(midDate); - - } - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); + public void setMeanPlane(final SensorMeanPlaneCrossing meanPlane) { + + if (this.meanPlane == null) { + this.meanPlane = meanPlane; + final long nbResults = meanPlane.getCachedResults().count(); + writer.format(Locale.US, + "sensor mean plane: sensorName %s minLine %d maxLine %d maxEval %d accuracy %22.15e normal %22.15e %22.15e %22.15e cachedResults %d", + dumpName, + meanPlane.getMinLine(), meanPlane.getMaxLine(), + meanPlane.getMaxEval(), meanPlane.getAccuracy(), + meanPlane.getMeanPlaneNormal().getX(), meanPlane.getMeanPlaneNormal().getY(), meanPlane.getMeanPlaneNormal().getZ(), + nbResults); + meanPlane.getCachedResults().forEach(result -> { + try { + writer.format(Locale.US, + " lineNumber %22.15e date %s target %22.15e %22.15e %22.15e targetDirection %22.15e %22.15e %22.15e %22.15e %22.15e %22.15e", + result.getLine(), convertDate(result.getDate()), + result.getTarget().getX(), result.getTarget().getY(), result.getTarget().getZ(), + result.getTargetDirection().getX(), + result.getTargetDirection().getY(), + result.getTargetDirection().getZ(), + result.getTargetDirectionDerivative().getZ(), + result.getTargetDirectionDerivative().getY(), + result.getTargetDirectionDerivative().getZ()); + } catch (RuggedException re) { + throw RuggedException.createInternalError(re); + } + }); + writer.format(Locale.US, "%n"); + + // ensure the transforms for mid date are dumped + final AbsoluteDate midDate = meanPlane.getSensor().getDate(0.5 * (meanPlane.getMinLine() + meanPlane.getMaxLine())); + meanPlane.getScToBody().getBodyToInertial(midDate); + meanPlane.getScToBody().getScToInertial(midDate); } } @@ -539,10 +521,8 @@ class Dump { * @param date date * @param pixelNumber number of the pixel * @param los los direction - * @exception RuggedException if date cannot be converted to UTC */ - public void setLOS(final AbsoluteDate date, final int pixelNumber, final Vector3D los) - throws RuggedException { + public void setLOS(final AbsoluteDate date, final int pixelNumber, final Vector3D los) { List<Pair<AbsoluteDate, Vector3D>> list = losMap.get(pixelNumber); if (list == null) { list = new ArrayList<Pair<AbsoluteDate, Vector3D>>(); @@ -563,10 +543,8 @@ class Dump { /** Set a datation pair. * @param lineNumber line number * @param date date - * @exception RuggedException if date cannot be converted to UTC */ - public void setDatation(final double lineNumber, final AbsoluteDate date) - throws RuggedException { + public void setDatation(final double lineNumber, final AbsoluteDate date) { for (final Pair<Double, AbsoluteDate> alreadyDumped : datation) { if (FastMath.abs(date.durationFrom(alreadyDumped.getSecond())) < 1.0e-12 && FastMath.abs(lineNumber - alreadyDumped.getFirst()) < 1.0e-12) { diff --git a/src/main/java/org/orekit/rugged/errors/DumpManager.java b/src/main/java/org/orekit/rugged/errors/DumpManager.java index eefb9fad..d351d511 100644 --- a/src/main/java/org/orekit/rugged/errors/DumpManager.java +++ b/src/main/java/org/orekit/rugged/errors/DumpManager.java @@ -59,7 +59,7 @@ public class DumpManager { * @exception RuggedException if debug dump is already active for this thread * or if debug file cannot be opened */ - public static void activate(final File file) throws RuggedException { + public static void activate(final File file) { if (isActive()) { throw new RuggedException(RuggedMessages.DEBUG_DUMP_ALREADY_ACTIVE); } else { @@ -75,7 +75,7 @@ public class DumpManager { /** Deactivate debug dump. * @exception RuggedException if debug dump is already active for this thread */ - public static void deactivate() throws RuggedException { + public static void deactivate() { if (isActive()) { DUMP.get().deactivate(); DUMP.set(null); @@ -140,12 +140,10 @@ public class DumpManager { * @param lightTimeCorrection flag for light time correction * @param aberrationOfLightCorrection flag for aberration of light correction * @param refractionCorrection flag for refraction correction - * @exception RuggedException if date cannot be converted to UTC */ public static void dumpDirectLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los, final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection, - final boolean refractionCorrection) - throws RuggedException { + final boolean refractionCorrection) { if (isActive()) { DUMP.get().dumpDirectLocation(date, sensorPosition, los, lightTimeCorrection, aberrationOfLightCorrection, refractionCorrection); @@ -154,10 +152,8 @@ public class DumpManager { /** Dump a direct location result. * @param gp resulting geodetic point - * @exception RuggedException if date cannot be converted to UTC */ - public static void dumpDirectLocationResult(final GeodeticPoint gp) - throws RuggedException { + public static void dumpDirectLocationResult(final GeodeticPoint gp) { if (isActive()) { DUMP.get().dumpDirectLocationResult(gp); } @@ -194,11 +190,9 @@ public class DumpManager { * @param index index of the transform * @param bodyToInertial transform from body frame to inertial frame * @param scToInertial transfrom from spacecraft frame to inertial frame - * @exception RuggedException if reference date cannot be converted to UTC */ public static void dumpTransform(final SpacecraftToObservedBody scToBody, final int index, - final Transform bodyToInertial, final Transform scToInertial) - throws RuggedException { + final Transform bodyToInertial, final Transform scToInertial) { if (isActive()) { DUMP.get().dumpTransform(scToBody, index, bodyToInertial, scToInertial); } @@ -206,10 +200,8 @@ public class DumpManager { /** Dump a sensor mean plane. * @param meanPlane mean plane associated with sensor - * @exception RuggedException if some frames cannot be computed at mid date */ - public static void dumpSensorMeanPlane(final SensorMeanPlaneCrossing meanPlane) - throws RuggedException { + public static void dumpSensorMeanPlane(final SensorMeanPlaneCrossing meanPlane) { if (isActive()) { DUMP.get().dumpSensorMeanPlane(meanPlane); } @@ -220,10 +212,8 @@ public class DumpManager { * @param date date * @param i pixel index * @param los pixel normalized line-of-sight - * @exception RuggedException if date cannot be converted to UTC */ - public static void dumpSensorLOS(final LineSensor sensor, final AbsoluteDate date, final int i, final Vector3D los) - throws RuggedException { + public static void dumpSensorLOS(final LineSensor sensor, final AbsoluteDate date, final int i, final Vector3D los) { if (isActive()) { DUMP.get().dumpSensorLOS(sensor, date, i, los); } @@ -233,10 +223,8 @@ public class DumpManager { * @param sensor sensor * @param lineNumber line number * @param date date - * @exception RuggedException if date cannot be converted to UTC */ - public static void dumpSensorDatation(final LineSensor sensor, final double lineNumber, final AbsoluteDate date) - throws RuggedException { + public static void dumpSensorDatation(final LineSensor sensor, final double lineNumber, final AbsoluteDate date) { if (isActive()) { DUMP.get().dumpSensorDatation(sensor, lineNumber, date); } diff --git a/src/main/java/org/orekit/rugged/errors/DumpReplayer.java b/src/main/java/org/orekit/rugged/errors/DumpReplayer.java index 43dae250..c8a7cb22 100644 --- a/src/main/java/org/orekit/rugged/errors/DumpReplayer.java +++ b/src/main/java/org/orekit/rugged/errors/DumpReplayer.java @@ -273,7 +273,7 @@ public class DumpReplayer { * @param file dump file to parse * @exception RuggedException if file cannot be parsed */ - public void parse(final File file) throws RuggedException { + public void parse(final File file) { try { final BufferedReader reader = new BufferedReader(new InputStreamReader(new FileInputStream(file), "UTF-8")); @@ -291,7 +291,7 @@ public class DumpReplayer { * @return rugged instance * @exception RuggedException if some data are inconsistent or incomplete */ - public Rugged createRugged() throws RuggedException { + public Rugged createRugged() { try { final RuggedBuilder builder = new RuggedBuilder(); @@ -306,8 +306,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void updateTile(final double latitude, final double longitude, final UpdatableTile tile) - throws RuggedException { + public void updateTile(final double latitude, final double longitude, final UpdatableTile tile) { for (final ParsedTile parsedTile : tiles) { if (parsedTile.isInterpolable(latitude, longitude)) { parsedTile.updateTile(tile); @@ -317,7 +316,6 @@ public class DumpReplayer { throw new RuggedException(RuggedMessages.NO_DEM_DATA, FastMath.toDegrees(latitude), FastMath.toDegrees(longitude)); } - }, 8); } @@ -411,7 +409,6 @@ public class DumpReplayer { // this should never happen throw RuggedException.createInternalError(e); } - } /** Get a sensor by name. @@ -436,9 +433,8 @@ public class DumpReplayer { * </p> * @param rugged Rugged instance on which calls will be performed * @return results of all dumped calls - * @exception RuggedException if a call fails */ - public Result[] execute(final Rugged rugged) throws RuggedException { + public Result[] execute(final Rugged rugged) { final Result[] results = new Result[calls.size()]; for (int i = 0; i < calls.size(); ++i) { results[i] = new Result(calls.get(i).expected, @@ -489,8 +485,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { try { if (fields.length < 1) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -514,8 +509,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 6 || !fields[0].equals(AE) || !fields[2].equals(F) || !fields[4].equals(FRAME)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); } @@ -568,7 +562,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public Object execute(final Rugged rugged) throws RuggedException { + public Object execute(final Rugged rugged) { return rugged.directLocation(date, position, los); } @@ -581,8 +575,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 6 || !fields[0].equals(LATITUDE) || !fields[2].equals(LONGITUDE) || !fields[4].equals(ELEVATION)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -626,8 +619,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 42 || !fields[0].equals(INDEX) || !fields[2].equals(BODY) || @@ -685,8 +677,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 13 || !fields[1].equals(LAT_MIN) || !fields[3].equals(LAT_STEP) || !fields[5].equals(LAT_ROWS) || !fields[7].equals(LON_MIN) || !fields[9].equals(LON_STEP) || !fields[11].equals(LON_COLS)) { @@ -717,8 +708,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 7 || !fields[1].equals(LAT_INDEX) || !fields[3].equals(LON_INDEX) || !fields[5].equals(ELEVATION)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -745,8 +735,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 16 || !fields[0].equals(SENSOR_NAME) || !fields[2].equals(LATITUDE) || !fields[4].equals(LONGITUDE) || !fields[6].equals(ELEVATION) || @@ -777,7 +766,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public Object execute(final Rugged rugged) throws RuggedException { + public Object execute(final Rugged rugged) { return rugged.inverseLocation(sensorName, point, minLine, maxLine); } @@ -791,8 +780,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 4 || !fields[0].equals(LINE_NUMBER) || !fields[2].equals(PIXEL_NUMBER)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); } @@ -809,8 +797,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 8 || !fields[0].equals(SENSOR_NAME) || !fields[2].equals(NB_PIXELS) || !fields[4].equals(POSITION)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -914,8 +901,7 @@ public class DumpReplayer { /** {@inheritDoc} */ @Override - public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) - throws RuggedException { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 6 || !fields[0].equals(SENSOR_NAME) || !fields[2].equals(LINE_NUMBER) || !fields[4].equals(RATE)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -934,10 +920,8 @@ public class DumpReplayer { * @param file dump file * @param line line to parse * @param global global parser to store parsed data - * @exception RuggedException if line is not supported */ - public static void parse(final int l, final File file, final String line, final DumpReplayer global) - throws RuggedException { + public static void parse(final int l, final File file, final String line, final DumpReplayer global) { final String trimmed = line.trim(); if (trimmed.length() == 0 || trimmed.startsWith(COMMENT_START)) { @@ -972,10 +956,8 @@ public class DumpReplayer { * @param line complete line * @param fields data fields from the line * @param global global parser to store parsed data - * @exception RuggedException if line cannot be parsed */ - public abstract void parse(int l, File file, String line, String[] fields, DumpReplayer global) - throws RuggedException; + public abstract void parse(int l, File file, String line, String[] fields, DumpReplayer global); } @@ -1042,10 +1024,8 @@ public class DumpReplayer { /** Update the tile according to the Digital Elevation Model. * @param tile to update - * @exception RuggedException if tile cannot be updated */ - public void updateTile(final UpdatableTile tile) - throws RuggedException { + public void updateTile(final UpdatableTile tile) { tile.setGeometry(minLatitude, minLongitude, latitudeStep, longitudeStep, @@ -1361,9 +1341,8 @@ public class DumpReplayer { /** Execute a call. * @param rugged Rugged instance on which called should be performed * @return result of the call - * @exception RuggedException if the call fails */ - public abstract Object execute(Rugged rugged) throws RuggedException; + public abstract Object execute(Rugged rugged); } diff --git a/src/main/java/org/orekit/rugged/errors/RuggedException.java b/src/main/java/org/orekit/rugged/errors/RuggedException.java index 635d8819..7f3a09f0 100644 --- a/src/main/java/org/orekit/rugged/errors/RuggedException.java +++ b/src/main/java/org/orekit/rugged/errors/RuggedException.java @@ -32,7 +32,7 @@ import org.hipparchus.exception.LocalizedException; * </p> * * @author Luc Maisonobe - + * @author Guylaine Prat */ public class RuggedException extends RuntimeException implements LocalizedException { diff --git a/src/main/java/org/orekit/rugged/errors/RuggedMessages.java b/src/main/java/org/orekit/rugged/errors/RuggedMessages.java index da289541..34515e6b 100644 --- a/src/main/java/org/orekit/rugged/errors/RuggedMessages.java +++ b/src/main/java/org/orekit/rugged/errors/RuggedMessages.java @@ -144,8 +144,7 @@ public enum RuggedMessages implements Localizable { /** {@inheritDoc} */ @Override public ResourceBundle newBundle(final String baseName, final Locale locale, final String format, - final ClassLoader loader, final boolean reload) - throws IllegalAccessException, InstantiationException, IOException { + final ClassLoader loader, final boolean reload) throws IOException { // The below is a copy of the default implementation. final String bundleName = toBundleName(baseName, locale); final String resourceName = toResourceName(bundleName, "utf8"); diff --git a/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java index b357f2a4..0ff21228 100644 --- a/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java @@ -183,8 +183,7 @@ public class BasicScanAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override - public double getElevation(final double latitude, final double longitude) - throws RuggedException { + public double getElevation(final double latitude, final double longitude) { DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY); final Tile tile = cache.getTile(latitude, longitude); return tile.interpolateElevation(latitude, longitude); diff --git a/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java index 395b5f4c..8c03e200 100644 --- a/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java @@ -39,8 +39,7 @@ public class IgnoreDEMAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los) - throws RuggedException { + final Vector3D position, final Vector3D los) { DumpManager.dumpAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID); return ellipsoid.pointOnGround(position, los, 0.0); } @@ -49,8 +48,7 @@ public class IgnoreDEMAlgorithm implements IntersectionAlgorithm { @Override public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid, final Vector3D position, final Vector3D los, - final NormalizedGeodeticPoint closeGuess) - throws RuggedException { + final NormalizedGeodeticPoint closeGuess) { DumpManager.dumpAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID); return intersection(ellipsoid, position, los); } diff --git a/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java index dbc8bf1b..e3e00c4c 100644 --- a/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java @@ -55,9 +55,7 @@ public interface IntersectionAlgorithm { * @param latitude ground point latitude * @param longitude ground point longitude * @return elevation at specified point - * @exception RuggedException if Digital Elevation Model does not cover point */ - double getElevation(double latitude, double longitude) - throws RuggedException; + double getElevation(double latitude, double longitude); } diff --git a/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java index 0fbd47a0..f76e6b76 100644 --- a/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java @@ -199,8 +199,8 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override - public double getElevation(final double latitude, final double longitude) - throws RuggedException { + public double getElevation(final double latitude, final double longitude) { + DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE); final Tile tile = cache.getTile(latitude, longitude); return tile.interpolateElevation(latitude, longitude); @@ -220,15 +220,12 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { * @param exitLon index to use for interpolating exit point elevation * @return point at which the line first enters ground, or null if does not enter * ground in the search sub-tile - * @exception RuggedException if intersection cannot be found - * @exception OrekitException if points cannot be converted to geodetic coordinates */ private NormalizedGeodeticPoint recurseIntersection(final int depth, final ExtendedEllipsoid ellipsoid, final Vector3D position, final Vector3D los, final MinMaxTreeTile tile, final NormalizedGeodeticPoint entry, final int entryLat, final int entryLon, - final NormalizedGeodeticPoint exit, final int exitLat, final int exitLon) - throws RuggedException, OrekitException { + final NormalizedGeodeticPoint exit, final int exitLat, final int exitLon) { if (depth > 30) { // this should never happen @@ -274,7 +271,7 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { final Vector3D crossingP = ellipsoid.pointAtLongitude(position, los, longitude); crossingGP = ellipsoid.transform(crossingP, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); - } catch (RuggedException re) { + } catch (RuggedException re) { // in some very rare cases of numerical noise, we miss the crossing point crossingGP = null; } @@ -344,7 +341,7 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { ellipsoid.transform(entry)); crossingGP = ellipsoid.transform(crossingP, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); - } catch (RuggedException re) { + } catch (RuggedException re) { // in some very rare cases of numerical noise, we miss the crossing point crossingGP = null; } @@ -426,16 +423,13 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { * @param exitLon index to use for interpolating exit point elevation * @return point at which the line first enters ground, or null if does not enter * ground in the search sub-tile - * @exception RuggedException if intersection cannot be found - * @exception OrekitException if points cannot be converted to geodetic coordinates */ private NormalizedGeodeticPoint noRecurseIntersection(final ExtendedEllipsoid ellipsoid, final Vector3D position, final Vector3D los, final MinMaxTreeTile tile, final NormalizedGeodeticPoint entry, final int entryLat, final int entryLon, - final int exitLat, final int exitLon) - throws OrekitException, RuggedException { + final int exitLat, final int exitLon) { NormalizedGeodeticPoint intersectionGP = null; double intersectionDot = Double.POSITIVE_INFINITY; @@ -502,12 +496,9 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { * @param position pixel position in ellipsoid frame * @param los pixel line-of-sight in ellipsoid frame * @return exit point - * @exception RuggedException if exit point cannot be found - * @exception OrekitException if geodetic coordinates cannot be computed */ private LimitPoint findExit(final Tile tile, final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los) - throws RuggedException, OrekitException { + final Vector3D position, final Vector3D los) { // look for an exit at bottom final double reference = tile.getMinimumLongitude(); @@ -629,11 +620,9 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { * @param cartesian Cartesian point * @param side if true, the point is on a side limit, otherwise * it is on a top/bottom limit - * @exception OrekitException if geodetic coordinates cannot be computed */ LimitPoint(final ExtendedEllipsoid ellipsoid, final double referenceLongitude, - final Vector3D cartesian, final boolean side) - throws OrekitException { + final Vector3D cartesian, final boolean side) { this(ellipsoid.transform(cartesian, ellipsoid.getBodyFrame(), null, referenceLongitude), side); } diff --git a/src/main/java/org/orekit/rugged/linesensor/LineSensor.java b/src/main/java/org/orekit/rugged/linesensor/LineSensor.java index cdb946d8..132f0631 100644 --- a/src/main/java/org/orekit/rugged/linesensor/LineSensor.java +++ b/src/main/java/org/orekit/rugged/linesensor/LineSensor.java @@ -90,10 +90,8 @@ public class LineSensor { * @param date current date * @param i pixel index (must be between 0 and {@link #getNbPixels()} - 1 * @return pixel normalized line-of-sight - * @exception RuggedException if date cannot be handled */ - public Vector3D getLOS(final AbsoluteDate date, final int i) - throws RuggedException { + public Vector3D getLOS(final AbsoluteDate date, final int i) { final Vector3D l = los.getLOS(i, date); DumpManager.dumpSensorLOS(this, date, i, l); return l; @@ -106,8 +104,7 @@ public class LineSensor { * @exception RuggedException if date cannot be handled * @since 2.0 */ - public Vector3D getLOS(final AbsoluteDate date, final double i) - throws RuggedException { + public Vector3D getLOS(final AbsoluteDate date, final double i) { final int iInf = FastMath.max(0, FastMath.min(getNbPixels() - 2, (int) FastMath.floor(i))); final int iSup = iInf + 1; @@ -155,10 +152,8 @@ public class LineSensor { /** Get the date. * @param lineNumber line number * @return date corresponding to line number - * @exception RuggedException if date cannot be handled */ - public AbsoluteDate getDate(final double lineNumber) - throws RuggedException { + public AbsoluteDate getDate(final double lineNumber) { final AbsoluteDate date = datationModel.getDate(lineNumber); DumpManager.dumpSensorDatation(this, lineNumber, date); return date; @@ -167,10 +162,8 @@ public class LineSensor { /** Get the line number. * @param date date * @return line number corresponding to date - * @exception RuggedException if date cannot be handled */ - public double getLine(final AbsoluteDate date) - throws RuggedException { + public double getLine(final AbsoluteDate date) { final double lineNumber = datationModel.getLine(date); DumpManager.dumpSensorDatation(this, lineNumber, date); return lineNumber; diff --git a/src/main/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossing.java b/src/main/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossing.java index 0231541a..7b5ad762 100644 --- a/src/main/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossing.java +++ b/src/main/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossing.java @@ -38,7 +38,6 @@ import org.hipparchus.util.FastMath; import org.hipparchus.util.Precision; import org.orekit.frames.Transform; import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.rugged.utils.SpacecraftToObservedBody; import org.orekit.time.AbsoluteDate; import org.orekit.utils.Constants; @@ -103,15 +102,13 @@ public class SensorMeanPlaneCrossing { * @param aberrationOfLightCorrection flag for aberration of light correction. * @param maxEval maximum number of evaluations * @param accuracy accuracy to use for finding crossing line number - * @exception RuggedException if some frame conversion fails */ public SensorMeanPlaneCrossing(final LineSensor sensor, final SpacecraftToObservedBody scToBody, final int minLine, final int maxLine, final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection, - final int maxEval, final double accuracy) - throws RuggedException { + final int maxEval, final double accuracy) { this(sensor, scToBody, minLine, maxLine, lightTimeCorrection, aberrationOfLightCorrection, maxEval, accuracy, computeMeanPlaneNormal(sensor, minLine, maxLine), Stream.<CrossingResult>empty()); @@ -128,7 +125,6 @@ public class SensorMeanPlaneCrossing { * @param accuracy accuracy to use for finding crossing line number * @param meanPlaneNormal mean plane normal * @param cachedResults cached results - * @exception RuggedException if some frame conversion fails */ public SensorMeanPlaneCrossing(final LineSensor sensor, final SpacecraftToObservedBody scToBody, @@ -137,8 +133,7 @@ public class SensorMeanPlaneCrossing { final boolean aberrationOfLightCorrection, final int maxEval, final double accuracy, final Vector3D meanPlaneNormal, - final Stream<CrossingResult> cachedResults) - throws RuggedException { + final Stream<CrossingResult> cachedResults) { this.sensor = sensor; this.minLine = minLine; @@ -174,10 +169,8 @@ public class SensorMeanPlaneCrossing { * order corresponds to trigonometric order (i.e. counterclockwise). * </p> * @return normal of the mean plane - * @exception RuggedException if mid date cannot be handled */ - private static Vector3D computeMeanPlaneNormal(final LineSensor sensor, final int minLine, final int maxLine) - throws RuggedException { + private static Vector3D computeMeanPlaneNormal(final LineSensor sensor, final int minLine, final int maxLine) { final AbsoluteDate midDate = sensor.getDate(0.5 * (minLine + maxLine)); @@ -355,11 +348,8 @@ public class SensorMeanPlaneCrossing { * @param target target ground point * @return line number and target direction at mean plane crossing, * or null if search interval does not bracket a solution - * @exception RuggedException if geometry cannot be computed for some line or - * if the maximum number of evaluations is exceeded */ - public CrossingResult find(final Vector3D target) - throws RuggedException { + public CrossingResult find(final Vector3D target) { double crossingLine = midLine; Transform bodyToInert = midBodyToInert; @@ -524,13 +514,10 @@ public class SensorMeanPlaneCrossing { * @param initialGuess initial guess for the crossing line * @return line number and target direction at mean plane crossing, * or null if search interval does not bracket a solution - * @exception RuggedException if geometry cannot be computed for some line or - * if the maximum number of evaluations is exceeded */ - private CrossingResult slowFind(final PVCoordinates targetPV, final double initialGuess) - throws RuggedException { + private CrossingResult slowFind(final PVCoordinates targetPV, final double initialGuess) { + try { - // safety check final double startValue; if (initialGuess < minLine || initialGuess > maxLine) { @@ -543,14 +530,14 @@ public class SensorMeanPlaneCrossing { final double crossingLine = solver.solve(maxEval, new UnivariateFunction() { /** {@inheritDoc} */ @Override - public double value(final double x) throws RuggedExceptionWrapper { + public double value(final double x) { try { final AbsoluteDate date = sensor.getDate(x); final Vector3D[] targetDirection = evaluateLine(x, targetPV, scToBody.getBodyToInertial(date), scToBody.getScToInertial(date)); return 0.5 * FastMath.PI - FastMath.acos(Vector3D.dotProduct(targetDirection[0], meanPlaneNormal)); } catch (RuggedException re) { - throw new RuggedExceptionWrapper(re); + throw RuggedException.createInternalError(re); } } }, minLine, maxLine, startValue); @@ -563,8 +550,6 @@ public class SensorMeanPlaneCrossing { } catch (MathIllegalArgumentException nbe) { return null; - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); } } diff --git a/src/main/java/org/orekit/rugged/linesensor/SensorPixelCrossing.java b/src/main/java/org/orekit/rugged/linesensor/SensorPixelCrossing.java index 2d0e3c13..b94d5c8a 100644 --- a/src/main/java/org/orekit/rugged/linesensor/SensorPixelCrossing.java +++ b/src/main/java/org/orekit/rugged/linesensor/SensorPixelCrossing.java @@ -23,7 +23,6 @@ import org.hipparchus.exception.MathIllegalArgumentException; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.time.AbsoluteDate; /** Class devoted to locate where ground point crosses a sensor line. @@ -69,20 +68,19 @@ public class SensorPixelCrossing { * @param date current date * @return pixel location ({@code Double.NaN} if the first and last * pixels of the line do not bracket a location) - * @exception RuggedException if the maximum number of evaluations is exceeded */ - public double locatePixel(final AbsoluteDate date) throws RuggedException { + public double locatePixel(final AbsoluteDate date) { try { // set up function evaluating to 0.0 where target matches pixel final UnivariateFunction f = new UnivariateFunction() { /** {@inheritDoc} */ @Override - public double value(final double x) throws RuggedExceptionWrapper { + public double value(final double x) { try { return Vector3D.angle(cross, getLOS(date, x)) - 0.5 * FastMath.PI; } catch (RuggedException re) { - throw new RuggedExceptionWrapper(re); + throw RuggedException.createInternalError(re); } } }; @@ -95,8 +93,6 @@ public class SensorPixelCrossing { } catch (MathIllegalArgumentException nbe) { // there are no solutions in the search interval return Double.NaN; - } catch (RuggedExceptionWrapper rew) { - throw rew.getException(); } } @@ -104,10 +100,8 @@ public class SensorPixelCrossing { * @param date current date * @param x pixel index * @return interpolated direction for specified index - * @exception RuggedException if date cannot be handled */ - private Vector3D getLOS(final AbsoluteDate date, final double x) - throws RuggedException { + private Vector3D getLOS(final AbsoluteDate date, final double x) { // find surrounding pixels final int iInf = FastMath.max(0, FastMath.min(sensor.getNbPixels() - 2, (int) FastMath.floor(x))); diff --git a/src/main/java/org/orekit/rugged/raster/SimpleTile.java b/src/main/java/org/orekit/rugged/raster/SimpleTile.java index a9301882..1fc234a8 100644 --- a/src/main/java/org/orekit/rugged/raster/SimpleTile.java +++ b/src/main/java/org/orekit/rugged/raster/SimpleTile.java @@ -90,8 +90,7 @@ public class SimpleTile implements Tile { @Override public void setGeometry(final double newMinLatitude, final double newMinLongitude, final double newLatitudeStep, final double newLongitudeStep, - final int newLatitudeRows, final int newLongitudeColumns) - throws RuggedException { + final int newLatitudeRows, final int newLongitudeColumns) { this.minLatitude = newMinLatitude; this.minLongitude = newMinLongitude; this.latitudeStep = newLatitudeStep; @@ -115,7 +114,7 @@ public class SimpleTile implements Tile { /** {@inheritDoc} */ @Override - public void tileUpdateCompleted() throws RuggedException { + public void tileUpdateCompleted() { processUpdatedElevation(elevations); } @@ -229,8 +228,8 @@ public class SimpleTile implements Tile { /** {@inheritDoc} */ @Override - public void setElevation(final int latitudeIndex, final int longitudeIndex, final double elevation) - throws RuggedException { + public void setElevation(final int latitudeIndex, final int longitudeIndex, final double elevation) { + if (latitudeIndex < 0 || latitudeIndex > (latitudeRows - 1) || longitudeIndex < 0 || longitudeIndex > (longitudeColumns - 1)) { throw new RuggedException(RuggedMessages.OUT_OF_TILE_INDICES, @@ -265,8 +264,7 @@ public class SimpleTile implements Tile { * </p> */ @Override - public double interpolateElevation(final double latitude, final double longitude) - throws RuggedException { + public double interpolateElevation(final double latitude, final double longitude) { final double doubleLatitudeIndex = getDoubleLatitudeIndex(latitude); final double doubleLongitudeIndex = getDoubleLontitudeIndex(longitude); @@ -304,8 +302,7 @@ public class SimpleTile implements Tile { /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint cellIntersection(final GeodeticPoint p, final Vector3D los, - final int latitudeIndex, final int longitudeIndex) - throws RuggedException { + final int latitudeIndex, final int longitudeIndex) { // ensure neighboring cells to not fall out of tile final int iLat = FastMath.max(0, FastMath.min(latitudeRows - 2, latitudeIndex)); diff --git a/src/main/java/org/orekit/rugged/raster/Tile.java b/src/main/java/org/orekit/rugged/raster/Tile.java index d1369d2e..2756ac0c 100644 --- a/src/main/java/org/orekit/rugged/raster/Tile.java +++ b/src/main/java/org/orekit/rugged/raster/Tile.java @@ -113,10 +113,8 @@ public interface Tile extends UpdatableTile { } /** Hook called at the end of tile update completion. - * @exception RuggedException if something wrong occurs - * (missing data ...) */ - void tileUpdateCompleted() throws RuggedException; + void tileUpdateCompleted(); /** Get minimum latitude of grid interpolation points. * @return minimum latitude of grid interpolation points diff --git a/src/test/java/org/orekit/rugged/TestUtils.java b/src/test/java/org/orekit/rugged/TestUtils.java index d67cb3e2..39e8ea6d 100644 --- a/src/test/java/org/orekit/rugged/TestUtils.java +++ b/src/test/java/org/orekit/rugged/TestUtils.java @@ -159,8 +159,7 @@ public class TestUtils { public static void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf, ArrayList<TimeStampedPVCoordinates> satellitePVList, String absDate, - double px, double py, double pz, double vx, double vy, double vz) - throws OrekitException { + double px, double py, double pz, double vx, double vy, double vz) { AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); Vector3D position = new Vector3D(px, py, pz); @@ -186,11 +185,8 @@ public class TestUtils { } /** Create an Earth for Junit tests. - * @return the Earth as the WGS84 ellipsoid - * @throws OrekitException */ - public static BodyShape createEarth() - throws OrekitException { + public static BodyShape createEarth() { return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, Constants.WGS84_EARTH_FLATTENING, @@ -199,10 +195,8 @@ public class TestUtils { /** Created a gravity field. * @return normalized spherical harmonics coefficients - * @throws OrekitException */ - public static NormalizedSphericalHarmonicsProvider createGravityField() - throws OrekitException { + public static NormalizedSphericalHarmonicsProvider createGravityField() { return GravityFieldFactory.getNormalizedProvider(12, 12); } @@ -210,9 +204,8 @@ public class TestUtils { /** Create an orbit. * @param mu Earth gravitational constant * @return the orbit - * @throws OrekitException */ - public static Orbit createOrbit(double mu) throws OrekitException { + public static Orbit createOrbit(double mu) { // the following orbital parameters have been computed using // Orekit tutorial about phasing, using the following configuration: @@ -237,12 +230,10 @@ public class TestUtils { /** Create the propagator of an orbit. * @return propagator of the orbit - * @throws OrekitException */ public static Propagator createPropagator(BodyShape earth, NormalizedSphericalHarmonicsProvider gravityField, - Orbit orbit) - throws OrekitException { + Orbit orbit) { AttitudeProvider yawCompensation = new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)); SpacecraftState state = new SpacecraftState(orbit, @@ -304,12 +295,10 @@ public class TestUtils { /** Propagate an orbit between 2 given dates * @return a list of TimeStampedPVCoordinates - * @throws OrekitException */ public static List<TimeStampedPVCoordinates> orbitToPV(Orbit orbit, BodyShape earth, AbsoluteDate minDate, AbsoluteDate maxDate, - double step) - throws OrekitException { + double step) { Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth))); @@ -329,12 +318,10 @@ public class TestUtils { /** Propagate an attitude between 2 given dates * @return a list of TimeStampedAngularCoordinates - * @throws OrekitException */ public static List<TimeStampedAngularCoordinates> orbitToQ(Orbit orbit, BodyShape earth, AbsoluteDate minDate, AbsoluteDate maxDate, - double step) - throws OrekitException { + double step) { Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth))); diff --git a/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java b/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java index 0a222ec0..6617c818 100644 --- a/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java +++ b/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java @@ -713,8 +713,7 @@ public class RuggedBuilderTest { protected void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf, ArrayList<TimeStampedPVCoordinates> satellitePVList, String absDate, - double px, double py, double pz, double vx, double vy, double vz) - throws OrekitException { + double px, double py, double pz, double vx, double vy, double vz) { AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); Vector3D position = new Vector3D(px, py, pz); Vector3D velocity = new Vector3D(vx, vy, vz); @@ -734,20 +733,17 @@ public class RuggedBuilderTest { satelliteQList.add(pair); } - private BodyShape createEarth() - throws OrekitException { + private BodyShape createEarth() { return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, Constants.WGS84_EARTH_FLATTENING, FramesFactory.getITRF(IERSConventions.IERS_2010, true)); } - private NormalizedSphericalHarmonicsProvider createGravityField() - throws OrekitException { + private NormalizedSphericalHarmonicsProvider createGravityField() { return GravityFieldFactory.getNormalizedProvider(12, 12); } - private Orbit createOrbit(double mu) - throws OrekitException { + private Orbit createOrbit(double mu) { // the following orbital parameters have been computed using // Orekit tutorial about phasing, using the following configuration: // @@ -771,8 +767,7 @@ public class RuggedBuilderTest { private Propagator createPropagator(BodyShape earth, NormalizedSphericalHarmonicsProvider gravityField, - Orbit orbit) - throws OrekitException { + Orbit orbit) { AttitudeProvider yawCompensation = new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)); SpacecraftState state = new SpacecraftState(orbit, @@ -827,9 +822,7 @@ public class RuggedBuilderTest { private List<TimeStampedPVCoordinates> orbitToPV(Orbit orbit, BodyShape earth, AbsoluteDate minDate, AbsoluteDate maxDate, - double step) - throws OrekitException { - + double step) { Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth))); propagator.propagate(minDate); diff --git a/src/test/java/org/orekit/rugged/api/RuggedTest.java b/src/test/java/org/orekit/rugged/api/RuggedTest.java index f258f20a..e72f88cd 100644 --- a/src/test/java/org/orekit/rugged/api/RuggedTest.java +++ b/src/test/java/org/orekit/rugged/api/RuggedTest.java @@ -101,7 +101,7 @@ public class RuggedTest { @Ignore @Test public void testMayonVolcanoTiming() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { long t0 = System.currentTimeMillis(); int dimension = 2000; @@ -192,7 +192,7 @@ public class RuggedTest { @Test public void testLightTimeCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 400; @@ -270,7 +270,7 @@ public class RuggedTest { @Test public void testAberrationOfLightCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 400; @@ -326,7 +326,7 @@ public class RuggedTest { } @Test - public void testAtmosphericRefractionCorrection() throws RuggedException, OrekitException, URISyntaxException { + public void testAtmosphericRefractionCorrection() throws URISyntaxException { String sensorName = "line"; int dimension = 4000; @@ -438,7 +438,7 @@ public class RuggedTest { @Test public void testFlatBodyCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -500,7 +500,7 @@ public class RuggedTest { @Test public void testLocationSinglePoint() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -558,7 +558,7 @@ public class RuggedTest { @Test public void testLocationsinglePointNoCorrections() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -619,7 +619,7 @@ public class RuggedTest { @Test public void testBasicScan() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -682,7 +682,7 @@ public class RuggedTest { @Ignore @Test public void testInverseLocationTiming() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { long t0 = System.currentTimeMillis(); int dimension = 2000; @@ -792,7 +792,7 @@ public class RuggedTest { @Test public void testInverseLocation() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { checkInverseLocation(2000, false, false, 4.0e-7, 5.0e-6); checkInverseLocation(2000, false, true, 1.0e-5, 2.0e-7); checkInverseLocation(2000, true, false, 4.0e-7, 4.0e-7); @@ -801,7 +801,7 @@ public class RuggedTest { @Test public void testDateLocation() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { checkDateLocation(2000, false, false, 7.0e-7); checkDateLocation(2000, false, true, 2.0e-5); checkDateLocation(2000, true, false, 8.0e-7); @@ -810,7 +810,7 @@ public class RuggedTest { @Test public void testLineDatation() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { checkLineDatation(2000, 7.0e-7); checkLineDatation(10000, 8.0e-7); } @@ -1020,7 +1020,7 @@ public class RuggedTest { @Test public void testInverseLocCurvedLine() - throws RuggedException, URISyntaxException, OrekitException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -1076,7 +1076,7 @@ public class RuggedTest { private void checkInverseLocation(int dimension, boolean lightTimeCorrection, boolean aberrationOfLightCorrection, double maxLineError, double maxPixelError) - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -1170,28 +1170,28 @@ public class RuggedTest { @Test public void testInverseLocationDerivativesWithoutCorrections() - throws RuggedException, OrekitException { + { doTestInverseLocationDerivatives(2000, false, false, 8.0e-9, 3.0e-10, 5.0e-12, 9.0e-8); } @Test public void testInverseLocationDerivativesWithLightTimeCorrection() - throws RuggedException, OrekitException { + { doTestInverseLocationDerivatives(2000, true, false, 3.0e-9, 9.0e-9, 2.1e-12, 9.0e-8); } @Test public void testInverseLocationDerivativesWithAberrationOfLightCorrection() - throws RuggedException, OrekitException { + { doTestInverseLocationDerivatives(2000, false, true, 4.2e-10, 3.0e-10, 3.4e-12, 7.0e-8); } @Test public void testInverseLocationDerivativesWithAllCorrections() - throws RuggedException, OrekitException { + { doTestInverseLocationDerivatives(2000, true, true, 3.0e-10, 5.0e-10, 2.0e-12, 7.0e-8); } @@ -1204,8 +1204,6 @@ public class RuggedTest { * @param pixelTolerance * @param lineDerivativeRelativeTolerance * @param pixelDerivativeRelativeTolerance - * @throws RuggedException - * @throws OrekitException */ private void doTestInverseLocationDerivatives(int dimension, boolean lightTimeCorrection, @@ -1214,7 +1212,7 @@ public class RuggedTest { double pixelTolerance, double lineDerivativeRelativeTolerance, double pixelDerivativeRelativeTolerance) - throws RuggedException, OrekitException { + { try { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); @@ -1372,7 +1370,7 @@ public class RuggedTest { private void checkDateLocation(int dimension, boolean lightTimeCorrection, boolean aberrationOfLightCorrection, double maxDateError) - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -1451,7 +1449,7 @@ public class RuggedTest { } private void checkLineDatation(int dimension, double maxLineError) - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -1486,7 +1484,7 @@ public class RuggedTest { } @Test - public void testDistanceBetweenLOS() throws RuggedException { + public void testDistanceBetweenLOS() { InitInterRefiningTest refiningTest = new InitInterRefiningTest(); refiningTest.initRefiningTest(); @@ -1504,7 +1502,7 @@ public class RuggedTest { } @Test - public void testDistanceBetweenLOSDerivatives() throws RuggedException, NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { + public void testDistanceBetweenLOSDerivatives() throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { InitInterRefiningTest refiningTest = new InitInterRefiningTest(); refiningTest.initRefiningTest(); diff --git a/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java b/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java index dae89afa..37a99a8b 100644 --- a/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java +++ b/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java @@ -46,7 +46,7 @@ public class DumpReplayerTest { public TemporaryFolder tempFolder = new TemporaryFolder(); @Test - public void testDirectLoc01() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testDirectLoc01() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -69,7 +69,7 @@ public class DumpReplayerTest { } @Test - public void testDirectLoc02() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testDirectLoc02() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -92,7 +92,7 @@ public class DumpReplayerTest { } @Test - public void testDirectLoc03() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testDirectLoc03() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -115,7 +115,7 @@ public class DumpReplayerTest { } @Test - public void testDirectLoc04() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testDirectLoc04() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -146,7 +146,7 @@ public class DumpReplayerTest { } @Test - public void testInverseLoc01() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testInverseLoc01() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -168,7 +168,7 @@ public class DumpReplayerTest { } @Test - public void testInverseLoc02() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testInverseLoc02() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -190,7 +190,7 @@ public class DumpReplayerTest { } @Test - public void testInverseLoc03() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testInverseLoc03() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); @@ -212,7 +212,7 @@ public class DumpReplayerTest { } @Test - public void testCorruptedFiles() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testCorruptedFiles() throws URISyntaxException, IOException { String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath))); diff --git a/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java b/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java index 35845826..ad970b02 100644 --- a/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java +++ b/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java @@ -56,8 +56,7 @@ public abstract class AbstractAlgorithmTest { protected abstract IntersectionAlgorithm createAlgorithm(TileUpdater updater, int maxCachedTiles); @Test - public void testMayonVolcanoOnSubTileCorner() - throws RuggedException, OrekitException { + public void testMayonVolcanoOnSubTileCorner() { setUpMayonVolcanoContext(); @@ -94,8 +93,7 @@ public abstract class AbstractAlgorithmTest { } @Test - public void testMayonVolcanoWithinPixel() - throws RuggedException, OrekitException { + public void testMayonVolcanoWithinPixel() { setUpMayonVolcanoContext(); diff --git a/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java b/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java index f810f6be..954d030f 100644 --- a/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java +++ b/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java @@ -49,7 +49,7 @@ import org.orekit.utils.PVCoordinates; public class ConstantElevationAlgorithmTest { @Test - public void testDuvenhageComparison() throws RuggedException { + public void testDuvenhageComparison() { final Vector3D los = new Vector3D(-0.626242839, 0.0124194184, -0.7795291301); IntersectionAlgorithm duvenhage = new DuvenhageAlgorithm(new CheckedPatternElevationUpdater(FastMath.toRadians(1.0), 256, 150.0, 150.0), @@ -74,7 +74,7 @@ public class ConstantElevationAlgorithmTest { } @Test - public void testIgnoreDEMComparison() throws RuggedException { + public void testIgnoreDEMComparison() { final Vector3D los = new Vector3D(-0.626242839, 0.0124194184, -0.7795291301); IntersectionAlgorithm ignore = new IgnoreDEMAlgorithm(); IntersectionAlgorithm constantElevation = new ConstantElevationAlgorithm(0.0); diff --git a/src/test/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithmTest.java b/src/test/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithmTest.java index cf512a6c..46563207 100644 --- a/src/test/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithmTest.java +++ b/src/test/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithmTest.java @@ -45,7 +45,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testNumericalIssueAtTileExit() throws RuggedException, OrekitException { + public void testNumericalIssueAtTileExit() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); Vector3D position = new Vector3D(-3787079.6453602533, 5856784.405679551, 1655869.0582939098); @@ -56,7 +56,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testCrossingBeforeLineSegmentStart() throws RuggedException, OrekitException { + public void testCrossingBeforeLineSegmentStart() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); Vector3D position = new Vector3D(-3787079.6453602533, 5856784.405679551, 1655869.0582939098); @@ -67,7 +67,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testWrongPositionMissesGround() throws RuggedException, OrekitException { + public void testWrongPositionMissesGround() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); Vector3D position = new Vector3D(7.551889113912788E9, -3.173692685491814E10, 1.5727517321541348E9); @@ -81,7 +81,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testInconsistentTileUpdater() throws RuggedException, OrekitException { + public void testInconsistentTileUpdater() { final int n = 1201; final double size = FastMath.toRadians(1.0); updater = new TileUpdater() { @@ -112,7 +112,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testPureEastWestLOS() throws RuggedException, OrekitException { + public void testPureEastWestLOS() { updater = new CheckedPatternElevationUpdater(FastMath.toRadians(1.0),1201, 41.0, 1563.0); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); NormalizedGeodeticPoint gp = @@ -123,7 +123,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } @Test - public void testParallelLOS() throws RuggedException, OrekitException { + public void testParallelLOS() { double size = 0.125; int n = 129; double elevation1 = 0.0; @@ -192,8 +192,7 @@ public class DuvenhageAlgorithmTest extends AbstractAlgorithmTest { } - private NormalizedGeodeticPoint findExit(IntersectionAlgorithm algorithm, Tile tile, Vector3D position, Vector3D los) - throws RuggedException, OrekitException { + private NormalizedGeodeticPoint findExit(IntersectionAlgorithm algorithm, Tile tile, Vector3D position, Vector3D los) { try { Method findExit = DuvenhageAlgorithm.class.getDeclaredMethod("findExit", diff --git a/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java b/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java index 77cf236a..11f55389 100644 --- a/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java +++ b/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java @@ -29,7 +29,7 @@ public class MinMaxTreeTileTest { @Test public void testSizeTall() - throws RuggedException, SecurityException, NoSuchFieldException, + throws SecurityException, NoSuchFieldException, IllegalArgumentException, IllegalAccessException { MinMaxTreeTile tile = createTile(107, 19); Assert.assertEquals(9, tile.getLevels()); @@ -68,7 +68,7 @@ public class MinMaxTreeTileTest { @Test public void testSizeFat() - throws RuggedException, SecurityException, NoSuchFieldException, + throws SecurityException, NoSuchFieldException, IllegalArgumentException, IllegalAccessException { MinMaxTreeTile tile = createTile(4, 7); Assert.assertEquals(4, tile.getLevels()); @@ -96,12 +96,12 @@ public class MinMaxTreeTileTest { } @Test - public void testSinglePixel() throws RuggedException { + public void testSinglePixel() { Assert.assertEquals(0, createTile(1, 1).getLevels()); } @Test - public void testMinMax() throws RuggedException { + public void testMinMax() { for (int nbRows = 1; nbRows < 25; nbRows++) { for (int nbColumns = 1; nbColumns < 25; nbColumns++) { @@ -133,7 +133,7 @@ public class MinMaxTreeTileTest { } @Test - public void testLocateMinMax() throws RuggedException { + public void testLocateMinMax() { RandomGenerator random = new Well1024a(0xca9883209c6e740cl); for (int nbRows = 1; nbRows < 25; nbRows++) { for (int nbColumns = 1; nbColumns < 25; nbColumns++) { @@ -167,7 +167,7 @@ public class MinMaxTreeTileTest { } @Test - public void testIssue189() throws RuggedException { + public void testIssue189() { MinMaxTreeTile tile = new MinMaxTreeTileFactory().createTile(); tile.setGeometry(1.0, 2.0, 0.1, 0.2, 2, 2); tile.setElevation(0, 0, 1.0); @@ -182,14 +182,14 @@ public class MinMaxTreeTileTest { } @Test - public void testMergeLarge() throws RuggedException { + public void testMergeLarge() { MinMaxTreeTile tile = createTile(1201, 1201); Assert.assertEquals(21, tile.getLevels()); Assert.assertEquals( 7, tile.getMergeLevel(703, 97, 765, 59)); } @Test - public void testMergeLevel() throws RuggedException { + public void testMergeLevel() { for (int nbRows = 1; nbRows < 20; nbRows++) { for (int nbColumns = 1; nbColumns < 20; nbColumns++) { @@ -236,7 +236,7 @@ public class MinMaxTreeTileTest { } @Test - public void testSubTilesLimits() throws RuggedException { + public void testSubTilesLimits() { for (int nbRows = 1; nbRows < 25; nbRows++) { for (int nbColumns = 1; nbColumns < 25; nbColumns++) { @@ -335,7 +335,7 @@ public class MinMaxTreeTileTest { } - private MinMaxTreeTile createTile(int nbRows, int nbColumns) throws RuggedException { + private MinMaxTreeTile createTile(int nbRows, int nbColumns) { MinMaxTreeTile tile = new MinMaxTreeTileFactory().createTile(); tile.setGeometry(1.0, 2.0, 0.1, 0.2, nbRows, nbColumns); for (int i = 0; i < nbRows; ++i) { diff --git a/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java b/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java index 14cf298f..eb99602d 100644 --- a/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java @@ -51,7 +51,7 @@ public class FixedRotationTest { private List<Vector3D> raw; @Test - public void testIdentity() throws RuggedException, OrekitException { + public void testIdentity() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xaba71348a77d77cbl)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -73,7 +73,7 @@ public class FixedRotationTest { } @Test - public void testCombination() throws RuggedException, OrekitException { + public void testCombination() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xefac03d9be4d24b9l)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -138,7 +138,7 @@ public class FixedRotationTest { } @Test - public void testDerivatives() throws RuggedException, OrekitException { + public void testDerivatives() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xddae2b46b2207e08l)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -227,7 +227,7 @@ public class FixedRotationTest { } @Before - public void setUp() throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { final Vector3D normal = Vector3D.PLUS_I; final Vector3D fovCenter = Vector3D.PLUS_K; diff --git a/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java b/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java index cb8aed13..672f71ca 100644 --- a/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java @@ -52,7 +52,7 @@ public class PolynomialRotationTest { private List<Vector3D> raw; @Test - public void testIdentity() throws RuggedException, OrekitException { + public void testIdentity() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xbe0d9b530fe7f53cl)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -74,7 +74,7 @@ public class PolynomialRotationTest { } @Test - public void testFixedCombination() throws RuggedException, OrekitException { + public void testFixedCombination() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xdc4cfdea38edd2bbl)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -145,7 +145,7 @@ public class PolynomialRotationTest { } @Test - public void testDerivatives() throws RuggedException, OrekitException { + public void testDerivatives() { UniformRandomGenerator rng = new UniformRandomGenerator(new Well19937a(0xc60acfc04eb27935l)); UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(3, rng); for (int k = 0; k < 20; ++k) { @@ -243,7 +243,7 @@ public class PolynomialRotationTest { } @Before - public void setUp() throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { final Vector3D normal = Vector3D.PLUS_I; final Vector3D fovCenter = Vector3D.PLUS_K; diff --git a/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java b/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java index b045b92f..9a8ffeba 100644 --- a/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java @@ -65,7 +65,7 @@ import org.orekit.utils.TimeStampedPVCoordinates; public class SensorMeanPlaneCrossingTest { @Test - public void testPerfectLine() throws RuggedException, OrekitException { + public void testPerfectLine() { final Vector3D position = new Vector3D(1.5, Vector3D.PLUS_I); final Vector3D normal = Vector3D.PLUS_I; @@ -94,7 +94,7 @@ public class SensorMeanPlaneCrossingTest { } @Test - public void testNoisyLine() throws RuggedException, OrekitException { + public void testNoisyLine() { final RandomGenerator random = new Well19937a(0xf3ddb33785e12bdal); final Vector3D position = new Vector3D(1.5, Vector3D.PLUS_I); @@ -129,29 +129,29 @@ public class SensorMeanPlaneCrossingTest { } @Test - public void testDerivativeWithoutCorrections() throws RuggedException, OrekitException { + public void testDerivativeWithoutCorrections() { doTestDerivative(false, false, 3.1e-11); } @Test - public void testDerivativeLightTimeCorrection() throws RuggedException, OrekitException { + public void testDerivativeLightTimeCorrection() { doTestDerivative(true, false, 2.4e-7); } @Test - public void testDerivativeAberrationOfLightCorrection() throws RuggedException, OrekitException { + public void testDerivativeAberrationOfLightCorrection() { doTestDerivative(false, true, 1.1e-7); } @Test - public void testDerivativeWithAllCorrections() throws RuggedException, OrekitException { + public void testDerivativeWithAllCorrections() { doTestDerivative(true, true, 1.4e-7); } private void doTestDerivative(boolean lightTimeCorrection, boolean aberrationOfLightCorrection, double tol) - throws RuggedException, OrekitException { + { final Vector3D position = new Vector3D(1.5, Vector3D.PLUS_I); final Vector3D normal = Vector3D.PLUS_I; @@ -223,7 +223,7 @@ public class SensorMeanPlaneCrossingTest { @Test public void testSlowFind() - throws RuggedException, OrekitException, NoSuchMethodException, + throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { @@ -287,8 +287,8 @@ public class SensorMeanPlaneCrossingTest { 1.0e-15); } - private SpacecraftToObservedBody createInterpolator(LineSensor sensor) - throws RuggedException, OrekitException { + private SpacecraftToObservedBody createInterpolator(LineSensor sensor) { + Orbit orbit = new CircularOrbit(7173352.811913891, -4.029194321683225E-4, 0.0013530362644647786, FastMath.toRadians(98.63218182243709), @@ -312,8 +312,8 @@ public class SensorMeanPlaneCrossingTest { private List<TimeStampedPVCoordinates> orbitToPV(Orbit orbit, BodyShape earth, AbsoluteDate minDate, AbsoluteDate maxDate, - double step) - throws OrekitException { + double step) { + Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth))); propagator.propagate(minDate); @@ -332,8 +332,8 @@ public class SensorMeanPlaneCrossingTest { private List<TimeStampedAngularCoordinates> orbitToQ(Orbit orbit, BodyShape earth, AbsoluteDate minDate, AbsoluteDate maxDate, - double step) - throws OrekitException { + double step) { + Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth))); propagator.propagate(minDate); @@ -350,7 +350,7 @@ public class SensorMeanPlaneCrossingTest { } @Before - public void setUp() throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { TestUtils.clearFactories(); String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); diff --git a/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java b/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java index ab813e99..59655cf1 100644 --- a/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java @@ -33,8 +33,8 @@ public class CheckedPatternElevationUpdater implements TileUpdater { this.elevation2 = elevation2; } - public void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException { + public void updateTile(double latitude, double longitude, UpdatableTile tile) { + double step = size / (n - 1); double minLatitude = size * FastMath.floor(latitude / size); double minLongitude = size * FastMath.floor(longitude / size); diff --git a/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java b/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java index f9d1befe..3f5ee8d0 100644 --- a/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java @@ -40,8 +40,8 @@ public class CliffsElevationUpdater implements TileUpdater { this.n = n; } - public void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException { + public void updateTile(double latitude, double longitude, UpdatableTile tile) { + double step = size / (n - 1); double minLatitude = size * FastMath.floor(latitude / size); double minLongitude = size * FastMath.floor(longitude / size); diff --git a/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java b/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java index 45e927b3..43fefdc1 100644 --- a/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java @@ -107,8 +107,7 @@ public class RandomLandscapeUpdater implements TileUpdater { } @Override - public void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException { + public void updateTile(double latitude, double longitude, UpdatableTile tile) { double step = size / (n - 1); double minLatitude = size * FastMath.floor(latitude / size); diff --git a/src/test/java/org/orekit/rugged/raster/SimpleTileTest.java b/src/test/java/org/orekit/rugged/raster/SimpleTileTest.java index 5d7f96db..348a40da 100644 --- a/src/test/java/org/orekit/rugged/raster/SimpleTileTest.java +++ b/src/test/java/org/orekit/rugged/raster/SimpleTileTest.java @@ -65,7 +65,7 @@ public class SimpleTileTest { } @Test - public void testUpdate() throws RuggedException { + public void testUpdate() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(1.0, 2.0, 0.1, 0.2, 100, 200); @@ -103,7 +103,7 @@ public class SimpleTileTest { } @Test - public void testOutOfBoundsIndices() throws RuggedException { + public void testOutOfBoundsIndices() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(1.0, 2.0, 0.1, 0.2, 100, 200); @@ -116,7 +116,7 @@ public class SimpleTileTest { } @Test - public void testIndexShift() throws RuggedException { + public void testIndexShift() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(1.0, 2.0, 0.1, 0.2, 100, 200); @@ -164,7 +164,7 @@ public class SimpleTileTest { } @Test - public void testInterpolation() throws RuggedException { + public void testInterpolation() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 1.0, 1.0, 50, 50); tile.setElevation(20, 14, 91.0); @@ -179,7 +179,7 @@ public class SimpleTileTest { } @Test - public void testInterpolationWithinTolerance() throws RuggedException { + public void testInterpolationWithinTolerance() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 1.0, 1.0, 2, 2); tile.setElevation(0, 0, 91.0); @@ -195,7 +195,7 @@ public class SimpleTileTest { } @Test - public void testInterpolationOutOfTolerance() throws RuggedException { + public void testInterpolationOutOfTolerance() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 1.0, 1.0, 2, 2); tile.setElevation(0, 0, 91.0); @@ -211,7 +211,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersection() throws RuggedException { + public void testCellIntersection() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(20, 14, 91.0); @@ -239,7 +239,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersection2Solutions() throws RuggedException { + public void testCellIntersection2Solutions() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(20, 14, 91.0); @@ -270,7 +270,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersectionNoSolutions() throws RuggedException { + public void testCellIntersectionNoSolutions() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(20, 14, 91.0); @@ -290,7 +290,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersectionLinearOnly() throws RuggedException { + public void testCellIntersectionLinearOnly() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(0, 0, 30.0); @@ -319,7 +319,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersectionLinearIntersectionOutside() throws RuggedException { + public void testCellIntersectionLinearIntersectionOutside() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(0, 0, 30.0); @@ -339,7 +339,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersectionLinearNoIntersection() throws RuggedException { + public void testCellIntersectionLinearNoIntersection() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(0, 0, 30.0); @@ -359,7 +359,7 @@ public class SimpleTileTest { } @Test - public void testCellIntersectionConstant0() throws RuggedException { + public void testCellIntersectionConstant0() { SimpleTile tile = new SimpleTileFactory().createTile(); tile.setGeometry(0.0, 0.0, 0.025, 0.025, 50, 50); tile.setElevation(0, 0, 30.0); @@ -440,11 +440,9 @@ public class SimpleTileTest { } - private void checkOnTile(Tile tile, GeodeticPoint gpI) - throws RuggedException { + private void checkOnTile(Tile tile, GeodeticPoint gpI) { Assert.assertEquals(gpI.getAltitude(), tile.interpolateElevation(gpI.getLatitude(), gpI.getLongitude()), 1.0e-10); } - } diff --git a/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java b/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java index 5dd97dac..8f236d23 100644 --- a/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java +++ b/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java @@ -28,7 +28,7 @@ import org.orekit.rugged.raster.TilesCache; public class TilesCacheTest { @Test - public void testSingleTile() throws RuggedException { + public void testSingleTile() { CountingFactory factory = new CountingFactory(); TilesCache<SimpleTile> cache = new TilesCache<SimpleTile>(factory, new CheckedPatternElevationUpdater(FastMath.toRadians(3.0), 11, 10.0, 20.0), 1000); @@ -43,7 +43,7 @@ public class TilesCacheTest { } @Test - public void testEviction() throws RuggedException { + public void testEviction() { CountingFactory factory = new CountingFactory(); TilesCache<SimpleTile> cache = new TilesCache<SimpleTile>(factory, new CheckedPatternElevationUpdater(FastMath.toRadians(1.0), 11, 10.0, 20.0), 12); @@ -95,7 +95,7 @@ public class TilesCacheTest { } @Test - public void testExactEnd() throws RuggedException { + public void testExactEnd() { CountingFactory factory = new CountingFactory(); TilesCache<SimpleTile> cache = new TilesCache<SimpleTile>(factory, @@ -123,7 +123,7 @@ public class TilesCacheTest { } @Test - public void testNonContiguousFill() throws RuggedException { + public void testNonContiguousFill() { CountingFactory factory = new CountingFactory(); TilesCache<SimpleTile> cache = new TilesCache<SimpleTile>(factory, diff --git a/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java b/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java index ef196594..bd236256 100644 --- a/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java @@ -38,8 +38,8 @@ public class VolcanicConeElevationUpdater implements TileUpdater { this.n = n; } - public void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException { + public void updateTile(double latitude, double longitude, UpdatableTile tile) { + double step = size / (n - 1); double minLatitude = size * FastMath.floor(latitude / size); double minLongitude = size * FastMath.floor(longitude / size); @@ -58,5 +58,4 @@ public class VolcanicConeElevationUpdater implements TileUpdater { } } } - } diff --git a/src/test/java/org/orekit/rugged/refraction/AtmosphericRefractionTest.java b/src/test/java/org/orekit/rugged/refraction/AtmosphericRefractionTest.java index 63586b03..dd49730c 100644 --- a/src/test/java/org/orekit/rugged/refraction/AtmosphericRefractionTest.java +++ b/src/test/java/org/orekit/rugged/refraction/AtmosphericRefractionTest.java @@ -16,7 +16,7 @@ import org.orekit.rugged.los.TimeDependentLOS; public class AtmosphericRefractionTest { @Test - public void testBadConfig() throws RuggedException { + public void testBadConfig() { int dimension = 400; diff --git a/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java b/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java index ab2afbd2..cc2904d5 100644 --- a/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java +++ b/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java @@ -40,7 +40,7 @@ import java.util.List; public class MultiLayerModelTest extends AbstractAlgorithmTest { @Test - public void testAlmostNadir() throws OrekitException, RuggedException { + public void testAlmostNadir() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -61,7 +61,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { } @Test - public void testNoOpRefraction() throws OrekitException, RuggedException { + public void testNoOpRefraction() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -89,8 +89,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { @Test public void testReversedAtmosphere() - throws OrekitException, RuggedException, IllegalArgumentException, - IllegalAccessException, NoSuchFieldException, SecurityException { + throws IllegalArgumentException, IllegalAccessException, NoSuchFieldException, SecurityException { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -138,8 +137,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { @Test public void testTwoAtmospheres() - throws OrekitException, RuggedException, IllegalArgumentException, - IllegalAccessException, NoSuchFieldException, SecurityException { + throws IllegalArgumentException, IllegalAccessException, NoSuchFieldException, SecurityException { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -181,7 +179,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { } @Test - public void testMissingLayers() throws OrekitException, RuggedException { + public void testMissingLayers() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -206,7 +204,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { } @Test - public void testLayersBelowDEM() throws OrekitException, RuggedException { + public void testLayersBelowDEM() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -225,7 +223,7 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { } @Test - public void testDivingAngleChange() throws OrekitException, RuggedException { + public void testDivingAngleChange() { setUpMayonVolcanoContext(); final IntersectionAlgorithm algorithm = createAlgorithm(updater, 8); @@ -251,8 +249,8 @@ public class MultiLayerModelTest extends AbstractAlgorithmTest { } - private Vector3D los(final Vector3D position, final double angleFromNadir) - throws OrekitException { + private Vector3D los(final Vector3D position, final double angleFromNadir) { + final Vector3D nadir = earth.transform(position, earth.getBodyFrame(), null).getNadir(); final Rotation losRotation = new Rotation(nadir.orthogonal(), angleFromNadir, RotationConvention.VECTOR_OPERATOR); diff --git a/src/test/java/org/orekit/rugged/utils/ExtendedEllipsoidTest.java b/src/test/java/org/orekit/rugged/utils/ExtendedEllipsoidTest.java index bbd25487..75100472 100644 --- a/src/test/java/org/orekit/rugged/utils/ExtendedEllipsoidTest.java +++ b/src/test/java/org/orekit/rugged/utils/ExtendedEllipsoidTest.java @@ -41,7 +41,7 @@ import org.orekit.utils.IERSConventions; public class ExtendedEllipsoidTest { @Test - public void testPointAtLongitude() throws RuggedException, OrekitException { + public void testPointAtLongitude() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 3.0); @@ -55,7 +55,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLongitudeError() throws RuggedException, OrekitException { + public void testPointAtLongitudeError() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); double longitude = 1.25; @@ -73,7 +73,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitude() throws RuggedException, OrekitException { + public void testPointAtLatitude() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 3.0); @@ -88,7 +88,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeTwoPointsSameSide() throws RuggedException, OrekitException { + public void testPointAtLatitudeTwoPointsSameSide() { // the line of sight is almost parallel an iso-latitude cone generatrix // the spacecraft is at latitude lTarget - 0.951", and altitude 794.6km @@ -124,7 +124,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeTwoPointsOppositeSides() throws RuggedException, OrekitException { + public void testPointAtLatitudeTwoPointsOppositeSides() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 0.1); @@ -143,7 +143,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeAlmostEquator() throws RuggedException, OrekitException { + public void testPointAtLatitudeAlmostEquator() { Vector3D p = new Vector3D(5767483.098580201, 4259689.325372237, -41553.67750784925); Vector3D d = new Vector3D(-0.7403523952347795, -0.6701811835520302, 0.05230212180799747); double latitude = -3.469446951953614E-18; @@ -155,7 +155,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeErrorQuadraticEquation() throws RuggedException, OrekitException { + public void testPointAtLatitudeErrorQuadraticEquation() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 3.0); @@ -172,7 +172,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeErrorNappe() throws RuggedException, OrekitException { + public void testPointAtLatitudeErrorNappe() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 0.1); @@ -189,7 +189,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtAltitude() throws RuggedException, OrekitException { + public void testPointAtAltitude() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 3.0); @@ -202,7 +202,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtAltitudeStartInside() throws RuggedException, OrekitException { + public void testPointAtAltitudeStartInside() { Vector3D p = new Vector3D(322010.30, 6962.30, -644982.20); Vector3D d = new Vector3D(-1.0, -2.0, -3.0); @@ -215,7 +215,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtAltitudeError() throws RuggedException, OrekitException { + public void testPointAtAltitudeError() { Vector3D p = new Vector3D(3220103.0, 69623.0, -6449822.0); Vector3D d = new Vector3D(1.0, 2.0, 3.0); @@ -231,7 +231,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testConvertLOS() throws RuggedException, OrekitException { + public void testConvertLOS() { GeodeticPoint gp = new GeodeticPoint(-0.2, 1.8, 2400.0); Vector3D p = ellipsoid.transform(gp); @@ -251,7 +251,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeError() throws RuggedException, OrekitException { + public void testPointAtLatitudeError() { Vector3D p = new Vector3D(-3052690.88784496, 6481300.309857268, 25258.7478104745); Vector3D d = new Vector3D(0.6, -0.8, 0.0); @@ -269,7 +269,7 @@ public class ExtendedEllipsoidTest { } @Test - public void testPointAtLatitudeIssue1() throws RuggedException, OrekitException { + public void testPointAtLatitudeIssue1() { Vector3D position = new Vector3D(-1988136.619268088, -2905373.394638188, 6231185.484365295); Vector3D los = new Vector3D(0.3489121277213534, 0.3447806500507106, -0.8714279261531437); diff --git a/src/test/java/org/orekit/rugged/utils/GeodeticUtilities.java b/src/test/java/org/orekit/rugged/utils/GeodeticUtilities.java index cabacab8..3c76cef7 100644 --- a/src/test/java/org/orekit/rugged/utils/GeodeticUtilities.java +++ b/src/test/java/org/orekit/rugged/utils/GeodeticUtilities.java @@ -86,7 +86,6 @@ public class GeodeticUtilities { * Convert longitude (in decimal degrees) in degrees/minutes/seconds * @param longitudeInDecimalDegrees * @return the DMS angle - * @throws S2GeolibException */ static DMSangle convertLongitudeToDMS(double longitudeInDecimalDegrees) { @@ -99,14 +98,12 @@ public class GeodeticUtilities { } return convertToDMS(longitudeInDecimalDegrees, cardinalDirection); - } /** * Convert latitude (in decimal degrees) in degrees/minutes/seconds * @param latitudeInDecimalDegrees * @return the DMSangle - * @throws S2GeolibException */ public static DMSangle convertLatitudeToDMS(double latitudeInDecimalDegrees){ @@ -127,9 +124,8 @@ public class GeodeticUtilities { * @param angleInDecimalDegrees angle in decimal degrees * @param cardinalDirection the associated cardinal direction * @return the DMSangle - * @throws S2GeolibException */ - private static DMSangle convertToDMS(double angleInDecimalDegrees, String cardinalDirection) throws OrekitException{ + private static DMSangle convertToDMS(double angleInDecimalDegrees, String cardinalDirection) { // We know the cardinal direction so we work on |angleInDecimalDegrees| the positive value double angleInDD = FastMath.abs(angleInDecimalDegrees); @@ -184,9 +180,8 @@ class DMSangle { * @param minutes minutes part * @param seconds seconds part * @param cardinalName cardinal direction - * @throws S2GeolibException */ - public DMSangle(int degrees, int minutes, double seconds, String cardinalName) throws OrekitException { + public DMSangle(int degrees, int minutes, double seconds, String cardinalName) { this.degrees = degrees; this.minutes = minutes; this.seconds = seconds; diff --git a/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java b/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java index 558cb928..c64df549 100644 --- a/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java +++ b/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java @@ -61,8 +61,7 @@ import org.orekit.utils.TimeStampedPVCoordinates; public class RoughVisibilityEstimatorTest { @Test - public void testThreeOrbitsSpan() - throws RuggedException, OrekitException, URISyntaxException { + public void testThreeOrbitsSpan() throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -87,8 +86,7 @@ public class RoughVisibilityEstimatorTest { } @Test - public void testOneOrbitsSpan() - throws RuggedException, OrekitException, URISyntaxException { + public void testOneOrbitsSpan() throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -112,20 +110,17 @@ public class RoughVisibilityEstimatorTest { } - private BodyShape createEarth() - throws OrekitException { + private BodyShape createEarth() { return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, Constants.WGS84_EARTH_FLATTENING, FramesFactory.getITRF(IERSConventions.IERS_2010, true)); } - private NormalizedSphericalHarmonicsProvider createGravityField() - throws OrekitException { + private NormalizedSphericalHarmonicsProvider createGravityField() { return GravityFieldFactory.getNormalizedProvider(12, 12); } - private Orbit createOrbit(double mu) - throws OrekitException { + private Orbit createOrbit(double mu) { // the following orbital parameters have been computed using // Orekit tutorial about phasing, using the following configuration: // @@ -149,8 +144,7 @@ public class RoughVisibilityEstimatorTest { private Propagator createPropagator(BodyShape earth, NormalizedSphericalHarmonicsProvider gravityField, - Orbit orbit) - throws OrekitException { + Orbit orbit) { AttitudeProvider yawCompensation = new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)); SpacecraftState state = new SpacecraftState(orbit, diff --git a/src/test/java/org/orekit/rugged/utils/SpacecraftToObservedBodyTest.java b/src/test/java/org/orekit/rugged/utils/SpacecraftToObservedBodyTest.java index 439a7177..e236caba 100644 --- a/src/test/java/org/orekit/rugged/utils/SpacecraftToObservedBodyTest.java +++ b/src/test/java/org/orekit/rugged/utils/SpacecraftToObservedBodyTest.java @@ -71,7 +71,7 @@ public class SpacecraftToObservedBodyTest { @Test - public void testIssue256() throws RuggedException, OrekitException { + public void testIssue256() { AbsoluteDate minSensorDate = sensor.getDate(0); AbsoluteDate maxSensorDate = sensor.getDate(2000); diff --git a/src/tutorials/java/fr/cs/examples/DirectLocation.java b/src/tutorials/java/fr/cs/examples/DirectLocation.java index be4f57b9..bdb2f237 100644 --- a/src/tutorials/java/fr/cs/examples/DirectLocation.java +++ b/src/tutorials/java/fr/cs/examples/DirectLocation.java @@ -173,8 +173,8 @@ public class DirectLocation { private static void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf, ArrayList<TimeStampedPVCoordinates> satellitePVList, String absDate, - double px, double py, double pz, double vx, double vy, double vz) - throws OrekitException { + double px, double py, double pz, double vx, double vy, double vz) { + AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); Vector3D position = new Vector3D(px, py, pz); // in ITRF, unit: m Vector3D velocity = new Vector3D(vx, vy, vz); // in ITRF, unit: m/s diff --git a/src/tutorials/java/fr/cs/examples/DirectLocationWithDEM.java b/src/tutorials/java/fr/cs/examples/DirectLocationWithDEM.java index 83ae3199..f1d05658 100644 --- a/src/tutorials/java/fr/cs/examples/DirectLocationWithDEM.java +++ b/src/tutorials/java/fr/cs/examples/DirectLocationWithDEM.java @@ -182,8 +182,8 @@ public class DirectLocationWithDEM { private static void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf, ArrayList<TimeStampedPVCoordinates> satellitePVList, String absDate, - double px, double py, double pz, double vx, double vy, double vz) - throws OrekitException { + double px, double py, double pz, double vx, double vy, double vz) { + AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); Vector3D position = new Vector3D(px, py, pz); // in ITRF, unit: m Vector3D velocity = new Vector3D(vx, vy, vz); // in ITRF, unit: m/s @@ -221,8 +221,8 @@ public class DirectLocationWithDEM { } @Override - public void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException { + public void updateTile(double latitude, double longitude, UpdatableTile tile) { + double step = size / (n - 1); double minLatitude = size * FastMath.floor(latitude / size); double minLongitude = size * FastMath.floor(longitude / size); diff --git a/src/tutorials/java/fr/cs/examples/InverseLocation.java b/src/tutorials/java/fr/cs/examples/InverseLocation.java index 01dd414d..aadf6d86 100644 --- a/src/tutorials/java/fr/cs/examples/InverseLocation.java +++ b/src/tutorials/java/fr/cs/examples/InverseLocation.java @@ -225,8 +225,8 @@ public class InverseLocation { private static void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf, ArrayList<TimeStampedPVCoordinates> satellitePVList, String absDate, - double px, double py, double pz, double vx, double vy, double vz) - throws OrekitException { + double px, double py, double pz, double vx, double vy, double vz) { + AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); Vector3D position = new Vector3D(px, py, pz); // in ITRF, unit: m Vector3D velocity = new Vector3D(vx, vy, vz); // in ITRF, unit: m/s diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/GroundRefining.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/GroundRefining.java index c2e91d75..e98cea8d 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/GroundRefining.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/GroundRefining.java @@ -232,7 +232,7 @@ public class GroundRefining extends Refining { } /** Constructor */ - public GroundRefining() throws RuggedException, OrekitException { + public GroundRefining() { sensorName = "line"; pleiadesViewingModel = new PleiadesViewingModel(sensorName); @@ -243,7 +243,7 @@ public class GroundRefining extends Refining { * @param LineSensor line sensor * @return the GSD */ - private double[] computeGSD(final Rugged rugged, final LineSensor lineSensor) throws RuggedException { + private double[] computeGSD(final Rugged rugged, final LineSensor lineSensor) { // Get number of line int dimension = pleiadesViewingModel.getDimension(); diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/InterRefining.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/InterRefining.java index 11bb47b6..31d22ecd 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/InterRefining.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/InterRefining.java @@ -302,7 +302,7 @@ public class InterRefining extends Refining { } /** Constructor */ - public InterRefining() throws RuggedException, OrekitException { + public InterRefining() { sensorNameA = "SensorA"; final double incidenceAngleA = -5.0; @@ -324,7 +324,7 @@ public class InterRefining extends Refining { * @return GSD */ private double computeDistanceBetweenLOS(final Rugged ruggedA, final LineSensor lineSensorA, - final Rugged ruggedB, final LineSensor lineSensorB) throws RuggedException { + final Rugged ruggedB, final LineSensor lineSensorB) { // Get number of line of sensors int dimensionA = pleiadesViewingModelA.getDimension(); diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java index e3e7aa0b..e53d2ee6 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java @@ -52,7 +52,7 @@ public class Refining { /** * Constructor */ - public Refining() throws RuggedException { + public Refining() { } /** Apply disruptions on acquisition for roll, pitch and scale factor @@ -61,11 +61,9 @@ public class Refining { * @param rollValue rotation on roll value * @param pitchValue rotation on pitch value * @param factorValue scale factor - * @throws RuggedException */ public void applyDisruptions(final Rugged rugged, final String sensorName, - final double rollValue, final double pitchValue, final double factorValue) - throws OrekitException, RuggedException { + final double rollValue, final double pitchValue, final double factorValue) { rugged. getLineSensor(sensorName). @@ -93,11 +91,10 @@ public class Refining { * @param sensorName line sensor name * @param dimension number of line of the sensor * @return ground measurements generator (sensor to ground mapping) - * @throws RuggedException */ public GroundMeasurementGenerator generatePoints(final int lineSampling, final int pixelSampling, final Rugged rugged, final String sensorName, - final int dimension) throws RuggedException { + final int dimension) { GroundMeasurementGenerator measurements = new GroundMeasurementGenerator(rugged, sensorName, dimension); @@ -121,12 +118,10 @@ public class Refining { * @param sensorNameB line sensor name B * @param dimensionB dimension for acquisition B * @return inter measurements generator (sensor to sensor mapping) - * @throws RuggedException */ public InterMeasurementGenerator generatePoints(final int lineSampling, final int pixelSampling, final Rugged ruggedA, final String sensorNameA, final int dimensionA, - final Rugged ruggedB, final String sensorNameB, final int dimensionB) - throws RuggedException { + final Rugged ruggedB, final String sensorNameB, final int dimensionB) { // Outliers control final double outlierValue = 1e+2; @@ -157,11 +152,10 @@ public class Refining { * @param dimension dimension * @param noise Noise structure to generate noisy measurements * @return ground measurements generator (sensor to ground mapping) - * @throws RuggedException */ public GroundMeasurementGenerator generateNoisyPoints(final int lineSampling, final int pixelSampling, final Rugged rugged, final String sensorName, final int dimension, - final Noise noise) throws RuggedException { + final Noise noise) { // Generate ground measurements GroundMeasurementGenerator measurements = new GroundMeasurementGenerator(rugged, sensorName, dimension); @@ -187,12 +181,11 @@ public class Refining { * @param dimensionB dimension for acquisition B * @param noise noise structure to generate noisy measurements * @return inter-measurements generator (sensor to sensor mapping) - * @throws RuggedException */ public InterMeasurementGenerator generateNoisyPoints(final int lineSampling, final int pixelSampling, final Rugged ruggedA, final String sensorNameA, final int dimensionA, final Rugged ruggedB, final String sensorNameB, final int dimensionB, - final Noise noise) throws RuggedException { + final Noise noise) { // Outliers control final double outlierValue = 1.e+2; @@ -220,10 +213,9 @@ public class Refining { * @param groundMapping sensor to ground mapping * @param rugged Rugged instance * @param unit flag to know if distance is computed in meters (false) or with angular (true) - * @throws RuggedException */ public void computeMetrics(final SensorToGroundMapping groundMapping, - final Rugged rugged, final boolean unit) throws RuggedException { + final Rugged rugged, final boolean unit) { String stUnit = null; if(unit) { @@ -242,11 +234,10 @@ public class Refining { * @param ruggedA Rugged instance A * @param ruggedB Rugged instance B * @param unit flag to know if distance is computed in meters (false) or with angular (true) - * @throws RuggedException */ public void computeMetrics(final SensorToSensorMapping interMapping, final Rugged ruggedA, final Rugged ruggedB, - final boolean unit) throws RuggedException { + final boolean unit) { String stUnit = null; if(unit) stUnit="degrees"; @@ -262,9 +253,8 @@ public class Refining { * @param rugged Rugged instance * @param sensorName line sensor name * @param isSelected flag to known if factor parameter is selected or not - * @throws RuggedException */ - public void resetModel(final Rugged rugged, final String sensorName, final boolean isSelected) throws RuggedException { + public void resetModel(final Rugged rugged, final String sensorName, final boolean isSelected) { rugged. getLineSensor(sensorName). @@ -293,10 +283,9 @@ public class Refining { * @param convergenceThreshold threshold of convergence * @param measurements ground measurements * @param rugged Rugged instance - * @throws RuggedException */ public void optimization(final int maxIterations, final double convergenceThreshold, - final Observables measurements, final Rugged rugged) throws RuggedException { + final Observables measurements, final Rugged rugged) { System.out.format("Iterations max: %d\tconvergence threshold: %3.6e \n", maxIterations, convergenceThreshold); @@ -315,11 +304,10 @@ public class Refining { * @param convergenceThreshold threshold of convergence * @param measurements measurements * @param ruggeds Rugged instances A and B - * @throws RuggedException */ public void optimization(final int maxIterations, final double convergenceThreshold, final Observables measurements, - final Collection<Rugged> ruggeds) throws RuggedException { + final Collection<Rugged> ruggeds) { System.out.format("Iterations max: %d\tconvergence threshold: %3.6e \n", maxIterations, convergenceThreshold); @@ -349,11 +337,9 @@ public class Refining { * @param rollValue rotation on roll value * @param pitchValue rotation on pitch value * @param factorValue scale factor - * @throws RuggedException */ public void paramsEstimation(final Rugged rugged, final String sensorName, - final double rollValue, final double pitchValue, final double factorValue) - throws RuggedException { + final double rollValue, final double pitchValue, final double factorValue) { // Estimate Roll double estimatedRoll = rugged.getLineSensor(sensorName). diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java index 06192a02..e3b2efec 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java @@ -60,10 +60,8 @@ public class GroundMeasurementGenerator implements Measurable { * @param rugged Rugged instance * @param sensorName sensor name * @param dimension number of line of the sensor - * @throws RuggedException */ - public GroundMeasurementGenerator(final Rugged rugged, final String sensorName, final int dimension) - throws RuggedException { + public GroundMeasurementGenerator(final Rugged rugged, final String sensorName, final int dimension) { // Generate reference mapping this.groundMapping = new SensorToGroundMapping(rugged.getName(), sensorName); @@ -97,7 +95,7 @@ public class GroundMeasurementGenerator implements Measurable { } @Override - public void createMeasurement(final int lineSampling, final int pixelSampling) throws RuggedException { + public void createMeasurement(final int lineSampling, final int pixelSampling) { for (double line = 0; line < dimension; line += lineSampling) { @@ -119,8 +117,7 @@ public class GroundMeasurementGenerator implements Measurable { } @Override - public void createNoisyMeasurement(final int lineSampling, final int pixelSampling, final Noise noise) - throws RuggedException { + public void createNoisyMeasurement(final int lineSampling, final int pixelSampling, final Noise noise) { // Estimate latitude and longitude errors (rad) final Vector3D latLongError = estimateLatLongError(); @@ -171,9 +168,8 @@ public class GroundMeasurementGenerator implements Measurable { /** Compute latitude and longitude errors * @return the latitude and longitude errors (rad) - * @throws RuggedException */ - private Vector3D estimateLatLongError() throws RuggedException { + private Vector3D estimateLatLongError() { final int pix = sensor.getNbPixels() / 2; final int line = (int) FastMath.floor(pix); // assumption : same number of line and pixels; diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java index e0938714..9dfe7d4e 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java @@ -84,11 +84,9 @@ public class InterMeasurementGenerator implements Measurable { * @param ruggedB Rugged instance corresponding to the viewing model B * @param sensorNameB sensor name B * @param dimensionB number of line for acquisition B - * @throws RuggedException */ public InterMeasurementGenerator(final Rugged ruggedA, final String sensorNameA, final int dimensionA, - final Rugged ruggedB, final String sensorNameB, final int dimensionB) - throws RuggedException { + final Rugged ruggedB, final String sensorNameB, final int dimensionB) { // Initialize parameters initParams(ruggedA, sensorNameA, dimensionA, ruggedB, sensorNameB, dimensionB); @@ -110,12 +108,10 @@ public class InterMeasurementGenerator implements Measurable { * @param sensorNameB sensor name B * @param dimensionB dimension for acquisition B * @param outlier limit value for outlier points - * @throws RuggedException */ public InterMeasurementGenerator(final Rugged ruggedA, final String sensorNameA, final int dimensionA, final Rugged ruggedB, final String sensorNameB, final int dimensionB, - final double outlier) - throws RuggedException { + final double outlier) { this(ruggedA, sensorNameA, dimensionA, ruggedB, sensorNameB, dimensionB); this.outlier = outlier; @@ -132,12 +128,10 @@ public class InterMeasurementGenerator implements Measurable { * @param outlier limit value for outlier points * @param earthConstraintWeight weight given to the Earth distance constraint * with respect to the LOS distance (between 0 and 1). - * @throws RuggedException */ public InterMeasurementGenerator(final Rugged ruggedA, final String sensorNameA, final int dimensionA, final Rugged ruggedB, final String sensorNameB, final int dimensionB, - final double outlier, final double earthConstraintWeight) - throws RuggedException { + final double outlier, final double earthConstraintWeight) { // Initialize parameters initParams(ruggedA, sensorNameA, dimensionA, ruggedB, sensorNameB, dimensionB); @@ -175,7 +169,7 @@ public class InterMeasurementGenerator implements Measurable { } @Override - public void createMeasurement(final int lineSampling, final int pixelSampling) throws RuggedException { + public void createMeasurement(final int lineSampling, final int pixelSampling) { // Search the sensor pixel seeing point final int minLine = 0; @@ -235,10 +229,8 @@ public class InterMeasurementGenerator implements Measurable { * @param lineSampling sampling along lines * @param pixelSampling sampling along columns * @param noise errors to apply to measure for pixel A and pixel B - * @throws RuggedException */ - public void createNoisyMeasurement(final int lineSampling, final int pixelSampling, final Noise noise) - throws RuggedException { + public void createNoisyMeasurement(final int lineSampling, final int pixelSampling, final Noise noise) { // Get noise features (errors) // [pixelA, pixelB] mean @@ -322,16 +314,14 @@ public class InterMeasurementGenerator implements Measurable { * @param rB Rugged instance B * @param sNameB sensor name B * @param dimB dimension for acquisition B - * @throws RuggedException */ private void initParams(final Rugged rA, final String sNameA, final int dimA, - final Rugged rB, final String sNameB, final int dimB) - throws RuggedException { + final Rugged rB, final String sNameB, final int dimB) { this.sensorNameB = sNameB; // Check that sensors's name is different if (sNameA.contains(sNameB)) { - throw new RuggedExceptionWrapper(new RuggedException(RuggedMessages.DUPLICATED_PARAMETER_NAME, sNameA)); + throw new RuggedException(RuggedMessages.DUPLICATED_PARAMETER_NAME, sNameA); } this.ruggedA = rA; diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/Measurable.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/Measurable.java index 0f778026..ea0b679d 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/Measurable.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/Measurable.java @@ -16,8 +16,6 @@ */ package fr.cs.examples.refiningPleiades.generators; -import org.orekit.rugged.errors.RuggedException; - /** For measurements generator. * @author Lucie Labat-Allee * @author Guylaine Prat @@ -27,23 +25,20 @@ public interface Measurable { /** Get the number of measurements * @return the number of measurements - * @throws RuggedException */ - int getMeasurementCount() throws RuggedException; + int getMeasurementCount(); /** Create measurements (without noise) * @param lineSampling line sampling * @param pixelSampling pixel sampling - * @throws RuggedException */ - void createMeasurement(int lineSampling, int pixelSampling) throws RuggedException; + void createMeasurement(int lineSampling, int pixelSampling); /** Create noisy measurements * @param lineSampling line sampling * @param pixelSampling pixel sampling * @param noise the noise to add to the measurements - * @throws RuggedException */ - void createNoisyMeasurement(int lineSampling, int pixelSampling, Noise noise) throws RuggedException; + void createNoisyMeasurement(int lineSampling, int pixelSampling, Noise noise); } diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java index 3efbc3e4..a9b98543 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java @@ -67,10 +67,8 @@ public class LocalisationMetrics { * @param measMapping Mapping of observations/measurements = the ground truth * @param rugged Rugged instance * @param computeAngular flag to know if distance is computed in meters (false) or with angular (true) - * @exception RuggedException if direct location fails */ - public LocalisationMetrics(final SensorToGroundMapping measMapping, final Rugged rugged, final boolean computeAngular) - throws RuggedException { + public LocalisationMetrics(final SensorToGroundMapping measMapping, final Rugged rugged, final boolean computeAngular) { // Initialization this.resMax = 0.0; @@ -85,11 +83,9 @@ public class LocalisationMetrics { * @param ruggedA Rugged instance corresponding to viewing model A * @param ruggedB Rugged instance corresponding to viewing model B * @param computeAngular flag to know if distance is computed in meters (false) or with angular (true) - * @exception RuggedException if direct location fails */ public LocalisationMetrics(final SensorToSensorMapping measMapping, final Rugged ruggedA, final Rugged ruggedB, - final boolean computeAngular) - throws RuggedException { + final boolean computeAngular) { // Initialization this.resMax = 0.0; @@ -108,10 +104,8 @@ public class LocalisationMetrics { * @param measMapping Mapping of observations/measurements = the ground truth * @param rugged Rugged instance * @param computeAngular flag to know if distance is computed in meters (false) or with angular (true) - * @exception RuggedException if direct location fails */ - public void computeGCPmetrics(final SensorToGroundMapping measMapping, final Rugged rugged, final boolean computeAngular) - throws RuggedException { + public void computeGCPmetrics(final SensorToGroundMapping measMapping, final Rugged rugged, final boolean computeAngular) { // Mapping of observations/measurements = the ground truth final Set<Map.Entry<SensorPixel, GeodeticPoint>> measurementsMapping; @@ -159,11 +153,9 @@ public class LocalisationMetrics { * @param ruggedA Rugged instance corresponding to viewing model A * @param ruggedB Rugged instance corresponding to viewing model B * @param computeAngular Flag to know if distance is computed in meters (false) or with angular (true) - * @exception RuggedException if direct location fails */ public void computeTiePointsMetrics(final SensorToSensorMapping measMapping, final Rugged ruggedA, final Rugged ruggedB, - final boolean computeAngular) - throws RuggedException { + final boolean computeAngular) { // Mapping of observations/measurements = the ground truth final Set<Map.Entry<SensorPixel, SensorPixel>> measurementsMapping; diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java index 6f59d297..d0fe5132 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java @@ -91,8 +91,7 @@ public class OrbitModel { final List<TimeStampedPVCoordinates> satellitePVList, final String absDate, final double px, final double py, final double pz, - final double vx, final double vy, final double vz) - throws OrekitException { + final double vx, final double vy, final double vz) { final AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps); final Vector3D position = new Vector3D(px, py, pz); @@ -120,9 +119,8 @@ public class OrbitModel { /** Create an Earth. * @return the Earth as the WGS84 ellipsoid - * @throws OrekitException */ - public BodyShape createEarth() throws OrekitException { + public BodyShape createEarth() { return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, Constants.WGS84_EARTH_FLATTENING, @@ -131,9 +129,8 @@ public class OrbitModel { /** Created a gravity field. * @return normalized spherical harmonics coefficients - * @throws OrekitException */ - public NormalizedSphericalHarmonicsProvider createGravityField() throws OrekitException { + public NormalizedSphericalHarmonicsProvider createGravityField() { return GravityFieldFactory.getNormalizedProvider(12, 12); } @@ -141,9 +138,8 @@ public class OrbitModel { /** Create an orbit at a chosen date. * @param mu Earth gravitational constant * @return the orbit - * @throws OrekitException */ - public Orbit createOrbit(final double mu, final AbsoluteDate date) throws OrekitException { + public Orbit createOrbit(final double mu, final AbsoluteDate date) { // the following orbital parameters have been computed using // Orekit tutorial about phasing, using the following configuration: @@ -195,8 +191,7 @@ public class OrbitModel { /** Get the offset. */ - private Rotation getOffset(final BodyShape earth, final Orbit orbit, final double shift) - throws OrekitException { + private Rotation getOffset(final BodyShape earth, final Orbit orbit, final double shift){ final LOFType type = LOFType.VVLH; final double roll = getPoly(lofTransformRollPoly, shift); @@ -219,8 +214,7 @@ public class OrbitModel { /** Create the attitude provider. */ - public AttitudeProvider createAttitudeProvider(final BodyShape earth, final Orbit orbit) - throws OrekitException { + public AttitudeProvider createAttitudeProvider(final BodyShape earth, final Orbit orbit) { if (userDefinedLOFTransform) { final LOFType type = LOFType.VVLH; @@ -247,8 +241,7 @@ public class OrbitModel { */ public List<TimeStampedPVCoordinates> orbitToPV(final Orbit orbit, final BodyShape earth, final AbsoluteDate minDate, final AbsoluteDate maxDate, - final double step) - throws OrekitException { + final double step) { final Propagator propagator = new KeplerianPropagator(orbit); @@ -271,8 +264,7 @@ public class OrbitModel { */ public List<TimeStampedAngularCoordinates> orbitToQ(final Orbit orbit, final BodyShape earth, final AbsoluteDate minDate, final AbsoluteDate maxDate, - final double step) - throws OrekitException { + final double step) { final Propagator propagator = new KeplerianPropagator(orbit); propagator.setAttitudeProvider(createAttitudeProvider(earth, orbit)); diff --git a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java index b54af4ef..9714793f 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java @@ -71,7 +71,7 @@ public class PleiadesViewingModel { * sensorName="line", incidenceAngle = 0.0, date = "2016-01-01T12:00:00.0" * </p> */ - public PleiadesViewingModel(final String sensorName) throws RuggedException, OrekitException { + public PleiadesViewingModel(final String sensorName) { this(sensorName, 0.0, "2016-01-01T12:00:00.0"); } @@ -80,11 +80,8 @@ public class PleiadesViewingModel { * @param sensorName sensor name * @param incidenceAngle incidence angle * @param referenceDate reference date - * @throws RuggedException - * @throws OrekitException */ - public PleiadesViewingModel(final String sensorName, final double incidenceAngle, final String referenceDate) - throws RuggedException, OrekitException { + public PleiadesViewingModel(final String sensorName, final double incidenceAngle, final String referenceDate) { this.sensorName = sensorName; this.date = referenceDate; @@ -126,7 +123,7 @@ public class PleiadesViewingModel { /** Get the reference date. */ - public AbsoluteDate getDatationReference() throws OrekitException { + public AbsoluteDate getDatationReference() { // We use Orekit for handling time and dates, and Rugged for defining the datation model: final TimeScale utc = TimeScalesFactory.getUTC(); @@ -136,13 +133,13 @@ public class PleiadesViewingModel { /** Get the min date. */ - public AbsoluteDate getMinDate() throws RuggedException { + public AbsoluteDate getMinDate() { return lineSensor.getDate(0); } /** Get the max date. */ - public AbsoluteDate getMaxDate() throws RuggedException { + public AbsoluteDate getMaxDate() { return lineSensor.getDate(DIMENSION); } @@ -167,7 +164,7 @@ public int getDimension() { /** Create the line sensor */ - private void createLineSensor() throws RuggedException, OrekitException { + private void createLineSensor() { // Offset of the MSI from center of mass of satellite // one line sensor -- GitLab