diff --git a/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java b/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java index f50e47c8e71c0358ce5a1f0814b86c796cee57f9..bea9eb7bb9c3f147bf4cb4f9bf84012876a02e77 100644 --- a/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java +++ b/src/main/java/org/orekit/rugged/adjustment/AdjustmentContext.java @@ -25,14 +25,11 @@ import java.util.Map; import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum; import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresProblem; -import org.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; +import org.orekit.rugged.adjustment.measurements.Observables; 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.adjustment.measurements.Observables; /** Create adjustment context for viewing model refining. * @author Lucie LabatAllee @@ -118,54 +115,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(); - } catch (OrekitExceptionWrapper oew) { - final OrekitException oe = oew.getException(); - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); + 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 3773d5c73c9b17226e81157a0c237afded58f006..dcbec62dc43710fe6bec050dd1c0a40a2801048a 100644 --- a/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilder.java @@ -34,16 +34,13 @@ 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.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; +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. @@ -82,20 +79,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() { @@ -109,60 +102,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; @@ -217,12 +200,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); - } catch (OrekitException oe) { - throw new OrekitExceptionWrapper(oe); - } }; return model; @@ -232,11 +209,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 41dd778e7fccc6527200dde289f5190e531f91c8..19a48a96316e7389aced5c4b22e155eee630cf18 100644 --- a/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/InterSensorsOptimizationProblemBuilder.java @@ -35,16 +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.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; +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; @@ -77,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>(); @@ -91,9 +86,7 @@ public class InterSensorsOptimizationProblemBuilder extends OptimizationProblemB this.initMapping(); } - /* (non-Javadoc) - * @see org.orekit.rugged.adjustment.OptimizationProblemBuilder#initMapping() - */ + /** {@inheritDoc} */ @Override protected void initMapping() { @@ -118,145 +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); - } catch (OrekitException oe) { - throw new OrekitExceptionWrapper(oe); + l += 2; // pass to the next evaluation + } } + + // distance result with Jacobian for all reference points + return new Pair<RealVector, RealMatrix>(value, jacobian); }; return model; @@ -266,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 2c607efedfb653e61ecad5606f6c0c12a1720da8..3272a098595cdd3f4a2cda609130658da51f41d3 100644 --- a/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java +++ b/src/main/java/org/orekit/rugged/adjustment/OptimizationProblemBuilder.java @@ -30,13 +30,10 @@ import org.hipparchus.optim.ConvergenceChecker; 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.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; +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.adjustment.measurements.Observables; import org.orekit.rugged.utils.DSGenerator; import org.orekit.utils.ParameterDriver; @@ -72,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; } @@ -94,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> @@ -131,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 @@ -151,19 +138,14 @@ abstract class OptimizationProblemBuilder { // Prevent parameters to exceed their prescribed bounds final ParameterValidator validator = params -> { - try { - int i = 0; - for (final ParameterDriver driver : this.drivers) { - - // let the parameter handle min/max clipping - driver.setNormalizedValue(params.getEntry(i)); - params.setEntry(i++, driver.getNormalizedValue()); - } - return params; + int i = 0; + for (final ParameterDriver driver : this.drivers) { - } catch (OrekitException oe) { - throw new OrekitExceptionWrapper(oe); + // let the parameter handle min/max clipping + driver.setNormalizedValue(params.getEntry(i)); + params.setEntry(i++, driver.getNormalizedValue()); } + return params; }; return validator; diff --git a/src/main/java/org/orekit/rugged/api/Rugged.java b/src/main/java/org/orekit/rugged/api/Rugged.java index c3b26db71a785847cd1ca49a64008ce548b27453..10c3af12d36f91fa8ffab48eaf5a93c198e7a8e0 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,39 +1145,33 @@ 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); } /** Get a sensor. * @param sensorName sensor name * @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 1113da3cbb342306b9f884ae5a23b536433b3117..7b8eac7d3eab4aa1a0c4f68d3ef669743bdd4a06 100644 --- a/src/main/java/org/orekit/rugged/api/RuggedBuilder.java +++ b/src/main/java/org/orekit/rugged/api/RuggedBuilder.java @@ -29,7 +29,6 @@ import org.hipparchus.exception.LocalizedCoreFormats; import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.orekit.bodies.OneAxisEllipsoid; -import org.orekit.errors.OrekitException; import org.orekit.frames.Frame; import org.orekit.frames.FramesFactory; import org.orekit.propagation.Propagator; @@ -183,28 +182,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 +408,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 +423,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 +459,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; @@ -581,15 +574,13 @@ public class RuggedBuilder { * @param storageStream stream from where to read previous instance {@link #storeInterpolator(OutputStream) * stored interpolator} (caller opened it and remains responsible for closing it) * @return the builder instance - * @exception RuggedException if storage stream cannot be parsed - * or if frames do not match the ones referenced in the storage stream * @see #setTrajectory(InertialFrameId, List, int, CartesianDerivativesFilter, List, int, AngularDerivativesFilter) * @see #setTrajectory(Frame, List, int, CartesianDerivativesFilter, List, int, AngularDerivativesFilter) * @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 +599,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) { @@ -630,7 +622,6 @@ public class RuggedBuilder { * </p> * @param storageStream stream where to store the interpolator * (caller opened it and remains responsible for closing it) - * @exception RuggedException if interpolator cannot be written to stream * @see #setEllipsoid(EllipsoidId, BodyRotatingFrameId) * @see #setEllipsoid(OneAxisEllipsoid) * @see #setTrajectory(InertialFrameId, List, int, CartesianDerivativesFilter, List, int, AngularDerivativesFilter) @@ -638,7 +629,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); @@ -648,23 +639,19 @@ public class RuggedBuilder { } /** Check frames consistency. - * @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())) { + // if frames have been set both by direct calls and by deserializing an interpolator dump and a mismatch occurs throw new RuggedException(RuggedMessages.FRAMES_MISMATCH_WITH_INTERPOLATOR_DUMP, ellipsoid.getBodyFrame().getName(), scToBody.getBodyFrame().getName()); } } /** Create a transform interpolator if needed. - * @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, - * or propagator fails. */ - private void createInterpolatorIfNeeded() throws RuggedException { + private void createInterpolatorIfNeeded() { if (ellipsoid == null) { throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setEllipsoid()"); @@ -684,7 +671,6 @@ public class RuggedBuilder { throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setTrajectory()"); } } - } /** Create a transform interpolator from positions and quaternions lists. @@ -701,8 +687,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 +696,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,49 +718,41 @@ 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, - final double tStep, final double overshootTolerance, - final double interpolationStep, final int interpolationNumber, - final CartesianDerivativesFilter pvFilter, - final AngularDerivativesFilter aFilter, - final Propagator propagator) - throws RuggedException { - try { + final AbsoluteDate minDate, final AbsoluteDate maxDate, + final double tStep, final double overshootTolerance, + final double interpolationStep, final int interpolationNumber, + final CartesianDerivativesFilter pvFilter, + final AngularDerivativesFilter aFilter, + final Propagator propagator) { + + // extract position/attitude samples from propagator + final List<TimeStampedPVCoordinates> positionsVelocities = + new ArrayList<TimeStampedPVCoordinates>(); + final List<TimeStampedAngularCoordinates> quaternions = + new ArrayList<TimeStampedAngularCoordinates>(); + propagator.setMasterMode(interpolationStep, new OrekitFixedStepHandler() { + + /** {@inheritDoc} */ + @Override + 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(); + positionsVelocities.add(new TimeStampedPVCoordinates(date, pv.getPosition(), pv.getVelocity(), Vector3D.ZERO)); + quaternions.add(new TimeStampedAngularCoordinates(date, q, Vector3D.ZERO, Vector3D.ZERO)); + } - // extract position/attitude samples from propagator - final List<TimeStampedPVCoordinates> positionsVelocities = - new ArrayList<TimeStampedPVCoordinates>(); - final List<TimeStampedAngularCoordinates> quaternions = - new ArrayList<TimeStampedAngularCoordinates>(); - propagator.setMasterMode(interpolationStep, new OrekitFixedStepHandler() { - - /** {@inheritDoc} */ - @Override - public void handleStep(final SpacecraftState currentState, final boolean isLast) - throws OrekitException { - final AbsoluteDate date = currentState.getDate(); - final PVCoordinates pv = currentState.getPVCoordinates(inertialFrame); - final Rotation q = currentState.getAttitude().getRotation(); - positionsVelocities.add(new TimeStampedPVCoordinates(date, pv.getPosition(), pv.getVelocity(), Vector3D.ZERO)); - quaternions.add(new TimeStampedAngularCoordinates(date, q, Vector3D.ZERO, Vector3D.ZERO)); - } - - }); - propagator.propagate(minDate.shiftedBy(-interpolationStep), maxDate.shiftedBy(interpolationStep)); - - // orbit/attitude to body converter - return createInterpolator(inertialFrame, bodyFrame, - minDate, maxDate, tStep, overshootTolerance, - positionsVelocities, interpolationNumber, - pvFilter, quaternions, interpolationNumber, - aFilter); - - } catch (OrekitException pe) { - throw new RuggedException(pe, pe.getSpecifier(), pe.getParts()); - } + }); + propagator.propagate(minDate.shiftedBy(-interpolationStep), maxDate.shiftedBy(interpolationStep)); + + // orbit/attitude to body converter + return createInterpolator(inertialFrame, bodyFrame, + minDate, maxDate, tStep, overshootTolerance, + positionsVelocities, interpolationNumber, + pvFilter, quaternions, interpolationNumber, + aFilter); } /** Set flag for light time correction. @@ -890,59 +866,45 @@ public class RuggedBuilder { /** Select inertial frame. * @param inertialFrameId inertial frame identifier * @return inertial frame - * @exception RuggedException if data needed for some frame cannot be loaded */ - private static Frame selectInertialFrame(final InertialFrameId inertialFrameId) - throws RuggedException { - - try { - // set up the inertial frame - switch (inertialFrameId) { - case GCRF : - return FramesFactory.getGCRF(); - case EME2000 : - return FramesFactory.getEME2000(); - case MOD : - return FramesFactory.getMOD(IERSConventions.IERS_1996); - case TOD : - return FramesFactory.getTOD(IERSConventions.IERS_1996, true); - case VEIS1950 : - return FramesFactory.getVeis1950(); - default : - // this should never happen - throw RuggedException.createInternalError(null); - } - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts().clone()); + private static Frame selectInertialFrame(final InertialFrameId inertialFrameId) { + + // set up the inertial frame + switch (inertialFrameId) { + case GCRF : + return FramesFactory.getGCRF(); + case EME2000 : + return FramesFactory.getEME2000(); + case MOD : + return FramesFactory.getMOD(IERSConventions.IERS_1996); + case TOD : + return FramesFactory.getTOD(IERSConventions.IERS_1996, true); + case VEIS1950 : + return FramesFactory.getVeis1950(); + default : + // this should never happen + throw RuggedException.createInternalError(null); } - } /** Select body rotating frame. * @param bodyRotatingFrame body rotating frame identifier * @return body rotating frame - * @exception RuggedException if data needed for some frame cannot be loaded */ - private static Frame selectBodyRotatingFrame(final BodyRotatingFrameId bodyRotatingFrame) - throws RuggedException { - - try { - // set up the rotating frame - switch (bodyRotatingFrame) { - case ITRF : - return FramesFactory.getITRF(IERSConventions.IERS_2010, true); - case ITRF_EQUINOX : - return FramesFactory.getITRFEquinox(IERSConventions.IERS_1996, true); - case GTOD : - return FramesFactory.getGTOD(IERSConventions.IERS_1996, true); - default : - // this should never happen - throw RuggedException.createInternalError(null); - } - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts().clone()); + private static Frame selectBodyRotatingFrame(final BodyRotatingFrameId bodyRotatingFrame) { + + // set up the rotating frame + switch (bodyRotatingFrame) { + case ITRF : + return FramesFactory.getITRF(IERSConventions.IERS_2010, true); + case ITRF_EQUINOX : + return FramesFactory.getITRFEquinox(IERSConventions.IERS_1996, true); + case GTOD : + return FramesFactory.getGTOD(IERSConventions.IERS_1996, true); + default : + // this should never happen + throw RuggedException.createInternalError(null); } - } /** Select ellipsoid. @@ -984,29 +946,27 @@ public class RuggedBuilder { // set up the algorithm switch (algorithmID) { - case DUVENHAGE : - return new DuvenhageAlgorithm(updater, maxCachedTiles, false); - case DUVENHAGE_FLAT_BODY : - return new DuvenhageAlgorithm(updater, maxCachedTiles, true); - case BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY : - return new BasicScanAlgorithm(updater, maxCachedTiles); - case CONSTANT_ELEVATION_OVER_ELLIPSOID : - return new ConstantElevationAlgorithm(constantElevation); - case IGNORE_DEM_USE_ELLIPSOID : - return new IgnoreDEMAlgorithm(); - default : - // this should never happen - throw RuggedException.createInternalError(null); + case DUVENHAGE : + return new DuvenhageAlgorithm(updater, maxCachedTiles, false); + case DUVENHAGE_FLAT_BODY : + return new DuvenhageAlgorithm(updater, maxCachedTiles, true); + case BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY : + return new BasicScanAlgorithm(updater, maxCachedTiles); + case CONSTANT_ELEVATION_OVER_ELLIPSOID : + return new ConstantElevationAlgorithm(constantElevation); + case IGNORE_DEM_USE_ELLIPSOID : + return new IgnoreDEMAlgorithm(); + default : + // this should never happen + throw RuggedException.createInternalError(null); } - } /** Build a {@link Rugged} instance. * @return built instance - * @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()"); } @@ -1022,7 +982,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 a7f29c7a70c56b9d91441e200a5f89e16b8e9d32..6420fa2520ef366529ea1173ca474735e2b86d95 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); } @@ -345,18 +332,12 @@ class Dump { /** Convert a date to string with high accuracy. * @param date computation date * @return converted date - * @exception RuggedException if date cannot be converted to UTC */ - private String convertDate(final AbsoluteDate date) - throws RuggedException { - try { - final DateTimeComponents dt = date.getComponents(TimeScalesFactory.getUTC()); - return String.format(Locale.US, "%04d-%02d-%02dT%02d:%02d:%017.14fZ", - dt.getDate().getYear(), dt.getDate().getMonth(), dt.getDate().getDay(), - dt.getTime().getHour(), dt.getTime().getMinute(), dt.getTime().getSecond()); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } + private String convertDate(final AbsoluteDate date) { + final DateTimeComponents dt = date.getComponents(TimeScalesFactory.getUTC()); + return String.format(Locale.US, "%04d-%02d-%02dT%02d:%02d:%017.14fZ", + dt.getDate().getYear(), dt.getDate().getMonth(), dt.getDate().getDay(), + dt.getTime().getHour(), dt.getTime().getMinute(), dt.getTime().getSecond()); } /** Convert a translation to string. @@ -498,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); } } @@ -545,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>>(); @@ -569,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 eefb9fad3033dd2d0a9416bbfe9419b41913bd3c..a63a0a1053188d7291521184cc684b1c011f08fa 100644 --- a/src/main/java/org/orekit/rugged/errors/DumpManager.java +++ b/src/main/java/org/orekit/rugged/errors/DumpManager.java @@ -56,10 +56,8 @@ public class DumpManager { /** Activate debug dump. * @param file dump file - * @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 { @@ -73,9 +71,8 @@ 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 +137,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 +149,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 +187,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 +197,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 +209,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 +220,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 cb7f67188269c2790134c3403c8d4d8916656ad2..085abcf85129c9d1309753c832caa8aa897af130 100644 --- a/src/main/java/org/orekit/rugged/errors/DumpReplayer.java +++ b/src/main/java/org/orekit/rugged/errors/DumpReplayer.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -45,7 +45,6 @@ import org.hipparchus.util.OpenIntToDoubleHashMap; import org.hipparchus.util.Pair; import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; -import org.orekit.errors.OrekitException; import org.orekit.frames.Frame; import org.orekit.frames.FramesFactory; import org.orekit.frames.Predefined; @@ -271,9 +270,8 @@ public class DumpReplayer { /** Parse a dump file. * @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")); @@ -289,9 +287,8 @@ public class DumpReplayer { /** Create a Rugged instance from parsed data. * @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 +303,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 +313,6 @@ public class DumpReplayer { throw new RuggedException(RuggedMessages.NO_DEM_DATA, FastMath.toDegrees(latitude), FastMath.toDegrees(longitude)); } - }, 8); } @@ -411,7 +406,6 @@ public class DumpReplayer { // this should never happen throw RuggedException.createInternalError(e); } - } /** Get a sensor by name. @@ -436,9 +430,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 +482,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 +506,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); } @@ -524,8 +515,6 @@ public class DumpReplayer { final Frame bodyFrame; try { bodyFrame = FramesFactory.getFrame(Predefined.valueOf(fields[5])); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); } catch (IllegalArgumentException iae) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); } @@ -539,9 +528,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 { - try { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 14 || !fields[0].equals(DATE) || !fields[2].equals(POSITION) || !fields[6].equals(LOS) || @@ -572,16 +559,12 @@ 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); } }); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } } - }, /** Parser for direct location result dump lines. */ @@ -589,8 +572,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); @@ -609,9 +591,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 { - try { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 10 || !fields[0].equals(MIN_DATE) || !fields[2].equals(MAX_DATE) || !fields[4].equals(T_STEP) || !fields[6].equals(TOLERANCE) || !fields[8].equals(INERTIAL_FRAME)) { @@ -628,11 +608,7 @@ public class DumpReplayer { } catch (IllegalArgumentException iae) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); } - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } } - }, /** Parser for observation transforms dump lines. */ @@ -640,8 +616,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) || @@ -699,8 +674,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)) { @@ -731,8 +705,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); @@ -759,8 +732,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) || @@ -791,7 +763,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); } @@ -805,8 +777,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); } @@ -823,8 +794,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); @@ -843,9 +813,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 { - try { + 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(MIN_LINE) || !fields[4].equals(MAX_LINE) || !fields[6].equals(MAX_EVAL) || !fields[8].equals(ACCURACY) || @@ -884,12 +852,7 @@ public class DumpReplayer { base += 15; } global.getSensor(sensorName).setMeanPlane(new ParsedMeanPlane(minLine, maxLine, maxEval, accuracy, normal, cachedResults)); - - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } } - }, /** Parser for sensor LOS dump lines. */ @@ -897,9 +860,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 { - try { + public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) { if (fields.length < 10 || !fields[0].equals(SENSOR_NAME) || !fields[2].equals(DATE) || !fields[4].equals(PIXEL_NUMBER) || !fields[6].equals(LOS)) { @@ -912,12 +873,7 @@ public class DumpReplayer { Double.parseDouble(fields[8]), Double.parseDouble(fields[9])); global.getSensor(sensorName).setLOS(date, pixelNumber, los); - - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } } - }, /** Parser for sensor datation dump lines. */ @@ -925,9 +881,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 { - try { + 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(DATE)) { throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line); @@ -936,13 +890,7 @@ public class DumpReplayer { final double lineNumber = Double.parseDouble(fields[3]); final AbsoluteDate date = new AbsoluteDate(fields[5], TimeScalesFactory.getUTC()); global.getSensor(sensorName).setDatation(lineNumber, date); - - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } - } - }, /** Parser for sensor rate dump lines. */ @@ -950,8 +898,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); @@ -970,10 +917,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)) { @@ -1008,10 +953,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); } @@ -1078,10 +1021,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, @@ -1397,9 +1338,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 47064b07d13589ee569036fc0afd895b5fc958cf..d4a6059deef7bd390ae918aae98f87e1ff1ee581 100644 --- a/src/main/java/org/orekit/rugged/errors/RuggedException.java +++ b/src/main/java/org/orekit/rugged/errors/RuggedException.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -32,10 +32,10 @@ import org.hipparchus.exception.LocalizedException; * </p> * * @author Luc Maisonobe - + * @author Guylaine Prat */ -public class RuggedException extends Exception implements LocalizedException { +public class RuggedException extends RuntimeException implements LocalizedException { /** Serializable UID. */ private static final long serialVersionUID = 20140309L; diff --git a/src/main/java/org/orekit/rugged/errors/RuggedExceptionWrapper.java b/src/main/java/org/orekit/rugged/errors/RuggedExceptionWrapper.java index c6c0449e6ba3a6e92a8807e802b8445bd910fbf4..dd5a1026c4511a5cc88bca19eb01f378c802f724 100644 --- a/src/main/java/org/orekit/rugged/errors/RuggedExceptionWrapper.java +++ b/src/main/java/org/orekit/rugged/errors/RuggedExceptionWrapper.java @@ -26,7 +26,11 @@ package org.orekit.rugged.errors; * which is distributed under the terms of the Apache License V2. * </p> * @author Luc Maisonobe + * @author Guylaine Prat + * @deprecated as of 3.0, this class is not used anymore, as {@link RuggedException} + * is now an unchecked exception */ +@Deprecated public class RuggedExceptionWrapper extends RuntimeException { /** serializable UID. */ diff --git a/src/main/java/org/orekit/rugged/errors/RuggedMessages.java b/src/main/java/org/orekit/rugged/errors/RuggedMessages.java index 972b11f3e444105142743857b6120f0d5a28faf6..6aeebd7eef5b74a74b2373e14a23a1eda84f87c7 100644 --- a/src/main/java/org/orekit/rugged/errors/RuggedMessages.java +++ b/src/main/java/org/orekit/rugged/errors/RuggedMessages.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -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 4960edb92fd32fdcd99fbdf0cedb406bdb025d14..c32a9fb9949735f3ffc51f9f88788c735c3d78b2 100644 --- a/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/BasicScanAlgorithm.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -16,16 +16,14 @@ */ package org.orekit.rugged.intersection; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.util.FastMath; import java.util.ArrayList; import java.util.List; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; -import org.orekit.errors.OrekitException; import org.orekit.rugged.api.AlgorithmId; import org.orekit.rugged.errors.DumpManager; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.raster.SimpleTile; import org.orekit.rugged.raster.SimpleTileFactory; import org.orekit.rugged.raster.Tile; @@ -66,137 +64,124 @@ public class BasicScanAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los) - throws RuggedException { - try { - - DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY); - - // find the tiles between the entry and exit point in the Digital Elevation Model - NormalizedGeodeticPoint entryPoint = null; - NormalizedGeodeticPoint exitPoint = null; - double minLatitude = Double.NaN; - double maxLatitude = Double.NaN; - double minLongitude = Double.NaN; - double maxLongitude = Double.NaN; - final List<SimpleTile> scannedTiles = new ArrayList<SimpleTile>(); - double centralLongitude = Double.NaN; - for (boolean changedMinMax = true; changedMinMax; changedMinMax = checkMinMax(scannedTiles)) { - - scannedTiles.clear(); - // compute entry and exit points - entryPoint = ellipsoid.transform(ellipsoid.pointAtAltitude(position, los, Double.isInfinite(hMax) ? 0.0 : hMax), - ellipsoid.getBodyFrame(), null, - Double.isNaN(centralLongitude) ? 0.0 : centralLongitude); - final SimpleTile entryTile = cache.getTile(entryPoint.getLatitude(), entryPoint.getLongitude()); - if (Double.isNaN(centralLongitude)) { - centralLongitude = entryTile.getMinimumLongitude(); - entryPoint = new NormalizedGeodeticPoint(entryPoint.getLatitude(), entryPoint.getLongitude(), - entryPoint.getAltitude(), centralLongitude); - } - addIfNotPresent(scannedTiles, entryTile); - - exitPoint = ellipsoid.transform(ellipsoid.pointAtAltitude(position, los, Double.isInfinite(hMin) ? 0.0 : hMin), - ellipsoid.getBodyFrame(), null, centralLongitude); - final SimpleTile exitTile = cache.getTile(exitPoint.getLatitude(), exitPoint.getLongitude()); - addIfNotPresent(scannedTiles, exitTile); - - minLatitude = FastMath.min(entryPoint.getLatitude(), exitPoint.getLatitude()); - maxLatitude = FastMath.max(entryPoint.getLatitude(), exitPoint.getLatitude()); - minLongitude = FastMath.min(entryPoint.getLongitude(), exitPoint.getLongitude()); - maxLongitude = FastMath.max(entryPoint.getLongitude(), exitPoint.getLongitude()); - - if (scannedTiles.size() > 1) { - // the entry and exit tiles are different, maybe other tiles should be added on the way - // in the spirit of simple and exhaustive, we add all tiles in a rectangular area - final double latStep = 0.5 * FastMath.min(entryTile.getLatitudeStep() * entryTile.getLatitudeRows(), - exitTile.getLatitudeStep() * exitTile.getLatitudeRows()); - final double lonStep = 0.5 * FastMath.min(entryTile.getLongitudeStep() * entryTile.getLongitudeColumns(), - exitTile.getLongitudeStep() * exitTile.getLongitudeColumns()); - for (double latitude = minLatitude; latitude <= maxLatitude; latitude += latStep) { - for (double longitude = minLongitude; longitude < maxLongitude; longitude += lonStep) { - addIfNotPresent(scannedTiles, cache.getTile(latitude, longitude)); - } + final Vector3D position, final Vector3D los) { + + DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY); + + // find the tiles between the entry and exit point in the Digital Elevation Model + NormalizedGeodeticPoint entryPoint = null; + NormalizedGeodeticPoint exitPoint = null; + double minLatitude = Double.NaN; + double maxLatitude = Double.NaN; + double minLongitude = Double.NaN; + double maxLongitude = Double.NaN; + final List<SimpleTile> scannedTiles = new ArrayList<SimpleTile>(); + double centralLongitude = Double.NaN; + for (boolean changedMinMax = true; changedMinMax; changedMinMax = checkMinMax(scannedTiles)) { + + scannedTiles.clear(); + // compute entry and exit points + entryPoint = ellipsoid.transform(ellipsoid.pointAtAltitude(position, los, Double.isInfinite(hMax) ? 0.0 : hMax), + ellipsoid.getBodyFrame(), null, + Double.isNaN(centralLongitude) ? 0.0 : centralLongitude); + final SimpleTile entryTile = cache.getTile(entryPoint.getLatitude(), entryPoint.getLongitude()); + if (Double.isNaN(centralLongitude)) { + centralLongitude = entryTile.getMinimumLongitude(); + entryPoint = new NormalizedGeodeticPoint(entryPoint.getLatitude(), entryPoint.getLongitude(), + entryPoint.getAltitude(), centralLongitude); + } + addIfNotPresent(scannedTiles, entryTile); + + exitPoint = ellipsoid.transform(ellipsoid.pointAtAltitude(position, los, Double.isInfinite(hMin) ? 0.0 : hMin), + ellipsoid.getBodyFrame(), null, centralLongitude); + final SimpleTile exitTile = cache.getTile(exitPoint.getLatitude(), exitPoint.getLongitude()); + addIfNotPresent(scannedTiles, exitTile); + + minLatitude = FastMath.min(entryPoint.getLatitude(), exitPoint.getLatitude()); + maxLatitude = FastMath.max(entryPoint.getLatitude(), exitPoint.getLatitude()); + minLongitude = FastMath.min(entryPoint.getLongitude(), exitPoint.getLongitude()); + maxLongitude = FastMath.max(entryPoint.getLongitude(), exitPoint.getLongitude()); + + if (scannedTiles.size() > 1) { + // the entry and exit tiles are different, maybe other tiles should be added on the way + // in the spirit of simple and exhaustive, we add all tiles in a rectangular area + final double latStep = 0.5 * FastMath.min(entryTile.getLatitudeStep() * entryTile.getLatitudeRows(), + exitTile.getLatitudeStep() * exitTile.getLatitudeRows()); + final double lonStep = 0.5 * FastMath.min(entryTile.getLongitudeStep() * entryTile.getLongitudeColumns(), + exitTile.getLongitudeStep() * exitTile.getLongitudeColumns()); + for (double latitude = minLatitude; latitude <= maxLatitude; latitude += latStep) { + for (double longitude = minLongitude; longitude < maxLongitude; longitude += lonStep) { + addIfNotPresent(scannedTiles, cache.getTile(latitude, longitude)); } } - } - // scan the tiles - NormalizedGeodeticPoint intersectionGP = null; - double intersectionDot = Double.POSITIVE_INFINITY; - for (final SimpleTile tile : scannedTiles) { - for (int i = latitudeIndex(tile, minLatitude); i <= latitudeIndex(tile, maxLatitude); ++i) { - for (int j = longitudeIndex(tile, minLongitude); j <= longitudeIndex(tile, maxLongitude); ++j) { - final NormalizedGeodeticPoint gp = tile.cellIntersection(entryPoint, ellipsoid.convertLos(entryPoint, los), i, j); - if (gp != null) { - - // improve the point, by projecting it back on the 3D line, fixing the small body curvature at cell level - final Vector3D delta = ellipsoid.transform(gp).subtract(position); - final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); - final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), - ellipsoid.getBodyFrame(), null); - final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), - projected.getLongitude(), - projected.getAltitude(), - gp.getLongitude()); - final NormalizedGeodeticPoint gpImproved = tile.cellIntersection(normalizedProjected, - ellipsoid.convertLos(normalizedProjected, los), - i, j); - - if (gpImproved != null) { - final Vector3D point = ellipsoid.transform(gpImproved); - final double dot = Vector3D.dotProduct(point.subtract(position), los); - if (dot < intersectionDot) { - intersectionGP = gpImproved; - intersectionDot = dot; - } - } + } + // scan the tiles + NormalizedGeodeticPoint intersectionGP = null; + double intersectionDot = Double.POSITIVE_INFINITY; + for (final SimpleTile tile : scannedTiles) { + for (int i = latitudeIndex(tile, minLatitude); i <= latitudeIndex(tile, maxLatitude); ++i) { + for (int j = longitudeIndex(tile, minLongitude); j <= longitudeIndex(tile, maxLongitude); ++j) { + final NormalizedGeodeticPoint gp = tile.cellIntersection(entryPoint, ellipsoid.convertLos(entryPoint, los), i, j); + if (gp != null) { + + // improve the point, by projecting it back on the 3D line, fixing the small body curvature at cell level + final Vector3D delta = ellipsoid.transform(gp).subtract(position); + final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); + final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), + ellipsoid.getBodyFrame(), null); + final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), + projected.getLongitude(), + projected.getAltitude(), + gp.getLongitude()); + final NormalizedGeodeticPoint gpImproved = tile.cellIntersection(normalizedProjected, + ellipsoid.convertLos(normalizedProjected, los), + i, j); + + if (gpImproved != null) { + final Vector3D point = ellipsoid.transform(gpImproved); + final double dot = Vector3D.dotProduct(point.subtract(position), los); + if (dot < intersectionDot) { + intersectionGP = gpImproved; + intersectionDot = dot; + } } + } } } - - return intersectionGP; - - } catch (OrekitException oe) { - // this should never happen - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); } + + return intersectionGP; } /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid, final Vector3D position, final Vector3D los, - final NormalizedGeodeticPoint closeGuess) - throws RuggedException { - try { - DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY); - final Vector3D delta = ellipsoid.transform(closeGuess).subtract(position); - final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); - final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), - ellipsoid.getBodyFrame(), null); - final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), - projected.getLongitude(), - projected.getAltitude(), - closeGuess.getLongitude()); - final Tile tile = cache.getTile(normalizedProjected.getLatitude(), - normalizedProjected.getLongitude()); - return tile.cellIntersection(normalizedProjected, - ellipsoid.convertLos(normalizedProjected, los), - tile.getFloorLatitudeIndex(normalizedProjected.getLatitude()), - tile.getFloorLongitudeIndex(normalizedProjected.getLongitude())); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } + final NormalizedGeodeticPoint closeGuess) { + DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY); + final Vector3D delta = ellipsoid.transform(closeGuess).subtract(position); + final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); + final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), + ellipsoid.getBodyFrame(), null); + final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), + projected.getLongitude(), + projected.getAltitude(), + closeGuess.getLongitude()); + final Tile tile = cache.getTile(normalizedProjected.getLatitude(), + normalizedProjected.getLongitude()); + return tile.cellIntersection(normalizedProjected, + ellipsoid.convertLos(normalizedProjected, los), + tile.getFloorLatitudeIndex(normalizedProjected.getLatitude()), + tile.getFloorLongitudeIndex(normalizedProjected.getLongitude())); } /** {@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/ConstantElevationAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/ConstantElevationAlgorithm.java index 70be321b59e982ad67e71264923eaf5df66a8084..e7a77fd1f7b08bf9a964061352ea80f394494851 100644 --- a/src/main/java/org/orekit/rugged/intersection/ConstantElevationAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/ConstantElevationAlgorithm.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -18,10 +18,8 @@ package org.orekit.rugged.intersection; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.orekit.bodies.GeodeticPoint; -import org.orekit.errors.OrekitException; import org.orekit.rugged.api.AlgorithmId; import org.orekit.rugged.errors.DumpManager; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.ExtendedEllipsoid; import org.orekit.rugged.utils.NormalizedGeodeticPoint; @@ -46,33 +44,23 @@ public class ConstantElevationAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los) - throws RuggedException { - try { - DumpManager.dumpAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID, constantElevation); - final Vector3D p = ellipsoid.pointAtAltitude(position, los, constantElevation); - final GeodeticPoint gp = ellipsoid.transform(p, ellipsoid.getFrame(), null); - return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), 0.0); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } + final Vector3D position, final Vector3D los) { + DumpManager.dumpAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID, constantElevation); + final Vector3D p = ellipsoid.pointAtAltitude(position, los, constantElevation); + final GeodeticPoint gp = ellipsoid.transform(p, ellipsoid.getFrame(), null); + return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), 0.0); } /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid, final Vector3D position, final Vector3D los, - final NormalizedGeodeticPoint closeGuess) - throws RuggedException { - try { - DumpManager.dumpAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID, constantElevation); - final Vector3D p = ellipsoid.pointAtAltitude(position, los, constantElevation); - final GeodeticPoint gp = ellipsoid.transform(p, ellipsoid.getFrame(), null); - return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), - closeGuess.getLongitude()); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } + final NormalizedGeodeticPoint closeGuess) { + DumpManager.dumpAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID, constantElevation); + final Vector3D p = ellipsoid.pointAtAltitude(position, los, constantElevation); + final GeodeticPoint gp = ellipsoid.transform(p, ellipsoid.getFrame(), null); + return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), + closeGuess.getLongitude()); } /** {@inheritDoc} diff --git a/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java b/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java index 395b5f4c5dc6d8c7cdc3a524a92bb5fc3a4e1a2d..7c3e6587f5ee301faf4edb0b5467acf5be21ae5f 100644 --- a/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/IgnoreDEMAlgorithm.java @@ -19,7 +19,6 @@ package org.orekit.rugged.intersection; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.orekit.rugged.api.AlgorithmId; import org.orekit.rugged.errors.DumpManager; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.ExtendedEllipsoid; import org.orekit.rugged.utils.NormalizedGeodeticPoint; @@ -39,8 +38,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 +47,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 17579c2f8375302fbbbe737a25327c9c219b4aff..41f67a3686c23a3cffe47c77c83d5aa9b9aa6ba9 100644 --- a/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/IntersectionAlgorithm.java @@ -17,7 +17,7 @@ package org.orekit.rugged.intersection; import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.orekit.rugged.errors.RuggedException; +import org.orekit.bodies.GeodeticPoint; import org.orekit.rugged.utils.ExtendedEllipsoid; import org.orekit.rugged.utils.NormalizedGeodeticPoint; @@ -31,10 +31,8 @@ public interface IntersectionAlgorithm { * @param position pixel position in ellipsoid frame * @param los pixel line-of-sight in ellipsoid frame * @return point at which the line first enters ground - * @exception RuggedException if intersection cannot be found */ - NormalizedGeodeticPoint intersection(ExtendedEllipsoid ellipsoid, Vector3D position, Vector3D los) - throws RuggedException; + NormalizedGeodeticPoint intersection(ExtendedEllipsoid ellipsoid, Vector3D position, Vector3D los); /** Refine intersection of line with Digital Elevation Model. * <p> @@ -49,19 +47,15 @@ public interface IntersectionAlgorithm { * @param los pixel line-of-sight in ellipsoid frame * @param closeGuess guess close to the real intersection * @return point at which the line first enters ground - * @exception RuggedException if intersection cannot be found */ NormalizedGeodeticPoint refineIntersection(ExtendedEllipsoid ellipsoid, Vector3D position, Vector3D los, - NormalizedGeodeticPoint closeGuess) - throws RuggedException; + NormalizedGeodeticPoint closeGuess); /** Get elevation at a given ground point. * @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 24098550a3037ddb9d9215ec8ab73401b50e319e..b88a52f0e066a5fbf091525b93a287a1df369800 100644 --- a/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java +++ b/src/main/java/org/orekit/rugged/intersection/duvenhage/DuvenhageAlgorithm.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -19,7 +19,6 @@ package org.orekit.rugged.intersection.duvenhage; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; -import org.orekit.errors.OrekitException; import org.orekit.rugged.api.AlgorithmId; import org.orekit.rugged.errors.DumpManager; import org.orekit.rugged.errors.RuggedException; @@ -69,153 +68,138 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm { /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los) - throws RuggedException { - try { - - DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE); + final Vector3D position, final Vector3D los) { - // compute intersection with ellipsoid - final NormalizedGeodeticPoint gp0 = ellipsoid.pointOnGround(position, los, 0.0); + DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE); - // compute atmosphere deviation + // compute intersection with ellipsoid + final NormalizedGeodeticPoint gp0 = ellipsoid.pointOnGround(position, los, 0.0); - // locate the entry tile along the line-of-sight - MinMaxTreeTile tile = cache.getTile(gp0.getLatitude(), gp0.getLongitude()); + // compute atmosphere deviation - NormalizedGeodeticPoint current = null; - double hMax = tile.getMaxElevation(); - while (current == null) { + // locate the entry tile along the line-of-sight + MinMaxTreeTile tile = cache.getTile(gp0.getLatitude(), gp0.getLongitude()); - // find where line-of-sight crosses tile max altitude - final Vector3D entryP = ellipsoid.pointAtAltitude(position, los, hMax + STEP); - if (Vector3D.dotProduct(entryP.subtract(position), los) < 0) { - // the entry point is behind spacecraft! - throw new RuggedException(RuggedMessages.DEM_ENTRY_POINT_IS_BEHIND_SPACECRAFT); - } - current = ellipsoid.transform(entryP, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); + NormalizedGeodeticPoint current = null; + double hMax = tile.getMaxElevation(); + while (current == null) { - if (tile.getLocation(current.getLatitude(), current.getLongitude()) != Tile.Location.HAS_INTERPOLATION_NEIGHBORS) { - // the entry point is in another tile - tile = cache.getTile(current.getLatitude(), current.getLongitude()); - hMax = FastMath.max(hMax, tile.getMaxElevation()); - current = null; - } + // find where line-of-sight crosses tile max altitude + final Vector3D entryP = ellipsoid.pointAtAltitude(position, los, hMax + STEP); + if (Vector3D.dotProduct(entryP.subtract(position), los) < 0) { + // the entry point is behind spacecraft! + throw new RuggedException(RuggedMessages.DEM_ENTRY_POINT_IS_BEHIND_SPACECRAFT); + } + current = ellipsoid.transform(entryP, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); + if (tile.getLocation(current.getLatitude(), current.getLongitude()) != Tile.Location.HAS_INTERPOLATION_NEIGHBORS) { + // the entry point is in another tile + tile = cache.getTile(current.getLatitude(), current.getLongitude()); + hMax = FastMath.max(hMax, tile.getMaxElevation()); + current = null; } - // loop along the path - while (true) { - - // find where line-of-sight exit tile - final LimitPoint exit = findExit(tile, ellipsoid, position, los); - - // compute intersection with Digital Elevation Model - final int entryLat = FastMath.max(0, - FastMath.min(tile.getLatitudeRows() - 1, - tile.getFloorLatitudeIndex(current.getLatitude()))); - final int entryLon = FastMath.max(0, - FastMath.min(tile.getLongitudeColumns() - 1, - tile.getFloorLongitudeIndex(current.getLongitude()))); - final int exitLat = FastMath.max(0, - FastMath.min(tile.getLatitudeRows() - 1, - tile.getFloorLatitudeIndex(exit.getPoint().getLatitude()))); - final int exitLon = FastMath.max(0, - FastMath.min(tile.getLongitudeColumns() - 1, - tile.getFloorLongitudeIndex(exit.getPoint().getLongitude()))); - NormalizedGeodeticPoint intersection = recurseIntersection(0, ellipsoid, position, los, tile, - current, entryLat, entryLon, - exit.getPoint(), exitLat, exitLon); + } + + // loop along the path + while (true) { + + // find where line-of-sight exit tile + final LimitPoint exit = findExit(tile, ellipsoid, position, los); + + // compute intersection with Digital Elevation Model + final int entryLat = FastMath.max(0, + FastMath.min(tile.getLatitudeRows() - 1, + tile.getFloorLatitudeIndex(current.getLatitude()))); + final int entryLon = FastMath.max(0, + FastMath.min(tile.getLongitudeColumns() - 1, + tile.getFloorLongitudeIndex(current.getLongitude()))); + final int exitLat = FastMath.max(0, + FastMath.min(tile.getLatitudeRows() - 1, + tile.getFloorLatitudeIndex(exit.getPoint().getLatitude()))); + final int exitLon = FastMath.max(0, + FastMath.min(tile.getLongitudeColumns() - 1, + tile.getFloorLongitudeIndex(exit.getPoint().getLongitude()))); + NormalizedGeodeticPoint intersection = recurseIntersection(0, ellipsoid, position, los, tile, + current, entryLat, entryLon, + exit.getPoint(), exitLat, exitLon); + + if (intersection != null) { + // we have found the intersection + return intersection; + } else if (exit.atSide()) { + // no intersection on this tile, we can proceed to next part of the line-of-sight + + // select next tile after current point + final Vector3D forward = new Vector3D(1.0, ellipsoid.transform(exit.getPoint()), STEP, los); + current = ellipsoid.transform(forward, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); + tile = cache.getTile(current.getLatitude(), current.getLongitude()); + + if (tile.interpolateElevation(current.getLatitude(), current.getLongitude()) >= current.getAltitude()) { + // extremely rare case! The line-of-sight traversed the Digital Elevation Model + // during the very short forward step we used to move to next tile + // we consider this point to be OK + return current; + } + + } else { + // this should never happen + // we should have left the loop with an intersection point + // try a fallback non-recursive search + intersection = noRecurseIntersection(ellipsoid, position, los, tile, + current, entryLat, entryLon, + exitLat, exitLon); if (intersection != null) { - // we have found the intersection return intersection; - } else if (exit.atSide()) { - // no intersection on this tile, we can proceed to next part of the line-of-sight - - // select next tile after current point - final Vector3D forward = new Vector3D(1.0, ellipsoid.transform(exit.getPoint()), STEP, los); - current = ellipsoid.transform(forward, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude()); - tile = cache.getTile(current.getLatitude(), current.getLongitude()); - - if (tile.interpolateElevation(current.getLatitude(), current.getLongitude()) >= current.getAltitude()) { - // extremely rare case! The line-of-sight traversed the Digital Elevation Model - // during the very short forward step we used to move to next tile - // we consider this point to be OK - return current; - } - } else { - - // this should never happen - // we should have left the loop with an intersection point - // try a fallback non-recursive search - intersection = noRecurseIntersection(ellipsoid, position, los, tile, - current, entryLat, entryLon, - exitLat, exitLon); - if (intersection != null) { - return intersection; - } else { - throw RuggedException.createInternalError(null); - } - + throw RuggedException.createInternalError(null); } - - } - - - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); } } /** {@inheritDoc} */ @Override public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid, - final Vector3D position, final Vector3D los, - final NormalizedGeodeticPoint closeGuess) - throws RuggedException { - try { + final Vector3D position, final Vector3D los, + final NormalizedGeodeticPoint closeGuess) { - DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE); - - if (flatBody) { - // under the (bad) flat-body assumption, the reference point must remain - // at DEM entry and exit, even if we already have a much better close guess :-( - // this is in order to remain consistent with other systems - final Tile tile = cache.getTile(closeGuess.getLatitude(), closeGuess.getLongitude()); - final Vector3D exitP = ellipsoid.pointAtAltitude(position, los, tile.getMinElevation()); - final Vector3D entryP = ellipsoid.pointAtAltitude(position, los, tile.getMaxElevation()); - final NormalizedGeodeticPoint entry = ellipsoid.transform(entryP, ellipsoid.getBodyFrame(), null, - tile.getMinimumLongitude()); - return tile.cellIntersection(entry, ellipsoid.convertLos(entryP, exitP), - tile.getFloorLatitudeIndex(closeGuess.getLatitude()), - tile.getFloorLongitudeIndex(closeGuess.getLongitude())); - } else { - final Vector3D delta = ellipsoid.transform(closeGuess).subtract(position); - final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); - final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), - ellipsoid.getBodyFrame(), null); - final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), - projected.getLongitude(), - projected.getAltitude(), - closeGuess.getLongitude()); - final Tile tile = cache.getTile(normalizedProjected.getLatitude(), - normalizedProjected.getLongitude()); - return tile.cellIntersection(normalizedProjected, ellipsoid.convertLos(normalizedProjected, los), - tile.getFloorLatitudeIndex(normalizedProjected.getLatitude()), - tile.getFloorLongitudeIndex(normalizedProjected.getLongitude())); - } - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); + DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE); + + if (flatBody) { + // under the (bad) flat-body assumption, the reference point must remain + // at DEM entry and exit, even if we already have a much better close guess :-( + // this is in order to remain consistent with other systems + final Tile tile = cache.getTile(closeGuess.getLatitude(), closeGuess.getLongitude()); + final Vector3D exitP = ellipsoid.pointAtAltitude(position, los, tile.getMinElevation()); + final Vector3D entryP = ellipsoid.pointAtAltitude(position, los, tile.getMaxElevation()); + final NormalizedGeodeticPoint entry = ellipsoid.transform(entryP, ellipsoid.getBodyFrame(), null, + tile.getMinimumLongitude()); + return tile.cellIntersection(entry, ellipsoid.convertLos(entryP, exitP), + tile.getFloorLatitudeIndex(closeGuess.getLatitude()), + tile.getFloorLongitudeIndex(closeGuess.getLongitude())); + } else { + final Vector3D delta = ellipsoid.transform(closeGuess).subtract(position); + final double s = Vector3D.dotProduct(delta, los) / los.getNormSq(); + final GeodeticPoint projected = ellipsoid.transform(new Vector3D(1, position, s, los), + ellipsoid.getBodyFrame(), null); + final NormalizedGeodeticPoint normalizedProjected = new NormalizedGeodeticPoint(projected.getLatitude(), + projected.getLongitude(), + projected.getAltitude(), + closeGuess.getLongitude()); + final Tile tile = cache.getTile(normalizedProjected.getLatitude(), + normalizedProjected.getLongitude()); + return tile.cellIntersection(normalizedProjected, ellipsoid.convertLos(normalizedProjected, los), + tile.getFloorLatitudeIndex(normalizedProjected.getLatitude()), + tile.getFloorLongitudeIndex(normalizedProjected.getLongitude())); } } /** {@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); @@ -235,15 +219,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 @@ -289,7 +270,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; } @@ -359,7 +340,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; } @@ -441,16 +422,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; @@ -517,12 +495,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(); @@ -644,11 +619,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 cdb946d8ffb6de438b3f2c51e559b5a50f647c19..abecdad9bd7aeb24b106cc0644b08eac87da6c33 100644 --- a/src/main/java/org/orekit/rugged/linesensor/LineSensor.java +++ b/src/main/java/org/orekit/rugged/linesensor/LineSensor.java @@ -23,7 +23,6 @@ import org.hipparchus.geometry.euclidean.threed.FieldVector3D; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; import org.orekit.rugged.errors.DumpManager; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.los.TimeDependentLOS; import org.orekit.rugged.utils.DSGenerator; import org.orekit.time.AbsoluteDate; @@ -90,10 +89,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; @@ -103,11 +100,9 @@ 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 * @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 +150,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 +160,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 0231541a104c86bfc05480e1c707ef52a81d9459..7b5ad762e9665d0c9dc3d3b43e3dccb1c3f7116d 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 2d0e3c13b7fe1fdd71a893f23d988081edae84dc..b94d5c8ac5d2c43762f0d705a66bbc99f4286442 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/los/FixedRotation.java b/src/main/java/org/orekit/rugged/los/FixedRotation.java index 0739913012b7f151443dd4f2c27a3d5ec0a823d8..0035ae8997cb3b97794583d898404f359a7469ca 100644 --- a/src/main/java/org/orekit/rugged/los/FixedRotation.java +++ b/src/main/java/org/orekit/rugged/los/FixedRotation.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -25,8 +25,6 @@ import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.RotationConvention; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; -import org.orekit.errors.OrekitException; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.DSGenerator; import org.orekit.utils.ParameterDriver; import org.orekit.utils.ParameterObserver; @@ -66,23 +64,19 @@ public class FixedRotation implements TimeIndependentLOSTransform { * @param angle rotation angle */ public FixedRotation(final String name, final Vector3D axis, final double angle) { + this.axis = axis; this.rotation = null; this.rDS = null; - try { - this.angleDriver = new ParameterDriver(name, angle, SCALE, -2 * FastMath.PI, 2 * FastMath.PI); - angleDriver.addObserver(new ParameterObserver() { - @Override - public void valueChanged(final double previousValue, final ParameterDriver driver) { - // reset rotations to null, they will be evaluated lazily if needed - rotation = null; - rDS = null; - } - }); - } catch (OrekitException oe) { - // this should never happen - throw RuggedException.createInternalError(oe); - } + this.angleDriver = new ParameterDriver(name, angle, SCALE, -2 * FastMath.PI, 2 * FastMath.PI); + angleDriver.addObserver(new ParameterObserver() { + @Override + public void valueChanged(final double previousValue, final ParameterDriver driver) { + // reset rotations to null, they will be evaluated lazily if needed + rotation = null; + rDS = null; + } + }); } /** {@inheritDoc} */ diff --git a/src/main/java/org/orekit/rugged/los/FixedZHomothety.java b/src/main/java/org/orekit/rugged/los/FixedZHomothety.java index 8b05b494811b879d7c200349d6d5524c6aab8c0a..a00406aecda658853a404bd445f9203eedfbd4b4 100644 --- a/src/main/java/org/orekit/rugged/los/FixedZHomothety.java +++ b/src/main/java/org/orekit/rugged/los/FixedZHomothety.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -22,8 +22,6 @@ import org.hipparchus.analysis.differentiation.DerivativeStructure; import org.hipparchus.geometry.euclidean.threed.FieldVector3D; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; -import org.orekit.errors.OrekitException; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.DSGenerator; import org.orekit.utils.ParameterDriver; import org.orekit.utils.ParameterObserver; @@ -62,22 +60,18 @@ public class FixedZHomothety implements TimeIndependentLOSTransform { * @param factorvalue homothety factor */ public FixedZHomothety(final String name, final double factorvalue) { + this.factor = factorvalue; this.factorDS = null; - try { - this.factorDriver = new ParameterDriver(name, factorvalue, SCALE, 0, Double.POSITIVE_INFINITY); - factorDriver.addObserver(new ParameterObserver() { - @Override - public void valueChanged(final double previousValue, final ParameterDriver driver) { - // reset factor to zero, they will be evaluated lazily if needed - factor = 0.0; - factorDS = null; - } - }); - } catch (OrekitException oe) { - // this should never happen - throw RuggedException.createInternalError(oe); - } + this.factorDriver = new ParameterDriver(name, factorvalue, SCALE, 0, Double.POSITIVE_INFINITY); + factorDriver.addObserver(new ParameterObserver() { + @Override + public void valueChanged(final double previousValue, final ParameterDriver driver) { + // reset factor to zero, they will be evaluated lazily if needed + factor = 0.0; + factorDS = null; + } + }); } /** {@inheritDoc} */ diff --git a/src/main/java/org/orekit/rugged/los/LOSBuilder.java b/src/main/java/org/orekit/rugged/los/LOSBuilder.java index 4d51d73e1086e605314a0662c72333215134fa7b..66daf936e0c1278eb6927c2481a7b20c77e707dc 100644 --- a/src/main/java/org/orekit/rugged/los/LOSBuilder.java +++ b/src/main/java/org/orekit/rugged/los/LOSBuilder.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -24,8 +24,6 @@ import java.util.stream.Stream; import org.hipparchus.analysis.differentiation.DerivativeStructure; import org.hipparchus.geometry.euclidean.threed.FieldVector3D; import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.orekit.errors.OrekitException; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.DSGenerator; import org.orekit.time.AbsoluteDate; import org.orekit.utils.ParameterDriver; @@ -234,14 +232,8 @@ public class LOSBuilder { } }; getParametersDrivers().forEach(driver -> { - try { - driver.addObserver(resettingObserver); - } catch (OrekitException oe) { - // this should never happen - throw RuggedException.createInternalError(oe); - } + driver.addObserver(resettingObserver); }); - } /** {@inheritDoc} */ diff --git a/src/main/java/org/orekit/rugged/los/PolynomialRotation.java b/src/main/java/org/orekit/rugged/los/PolynomialRotation.java index 3a978793042940e57c7407e8a6f4b7955aa25c3d..80c2fb582495407c4fea1e7307f7bd8856bdc2fc 100644 --- a/src/main/java/org/orekit/rugged/los/PolynomialRotation.java +++ b/src/main/java/org/orekit/rugged/los/PolynomialRotation.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -26,8 +26,6 @@ import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.RotationConvention; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; -import org.orekit.errors.OrekitException; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.DSGenerator; import org.orekit.time.AbsoluteDate; import org.orekit.utils.ParameterDriver; @@ -94,15 +92,10 @@ public class PolynomialRotation implements LOSTransform { angleDS = null; } }; - try { - for (int i = 0; i < angleCoeffs.length; ++i) { - coefficientsDrivers[i] = new ParameterDriver(name + "[" + i + "]", angleCoeffs[i], SCALE, - Double.NEGATIVE_INFINITY, Double.POSITIVE_INFINITY); - coefficientsDrivers[i].addObserver(resettingObserver); - } - } catch (OrekitException oe) { - // this should never happen - throw RuggedException.createInternalError(oe); + for (int i = 0; i < angleCoeffs.length; ++i) { + coefficientsDrivers[i] = new ParameterDriver(name + "[" + i + "]", angleCoeffs[i], SCALE, + Double.NEGATIVE_INFINITY, Double.POSITIVE_INFINITY); + coefficientsDrivers[i].addObserver(resettingObserver); } } diff --git a/src/main/java/org/orekit/rugged/raster/SimpleTile.java b/src/main/java/org/orekit/rugged/raster/SimpleTile.java index a93018822f44a3d30a64e090fce1caedbee88c5e..1fc234a8156ef8eba65a468206af1c64d2ceaf14 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 d1369d2edf888d3e46a4f437692c44652364de1d..81de1b64976bb0be5b35b114c9b8761eac39d66f 100644 --- a/src/main/java/org/orekit/rugged/raster/Tile.java +++ b/src/main/java/org/orekit/rugged/raster/Tile.java @@ -18,7 +18,6 @@ package org.orekit.rugged.raster; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.orekit.bodies.GeodeticPoint; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.utils.NormalizedGeodeticPoint; /** Interface representing a raster tile. @@ -113,10 +112,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 @@ -240,10 +237,8 @@ public interface Tile extends UpdatableTile { * @param latitudeIndex grid point index along latitude * @param longitudeIndex grid point index along longitude * @return elevation at grid point - * @exception RuggedException if indices are out of bound */ - double getElevationAtIndices(int latitudeIndex, int longitudeIndex) - throws RuggedException; + double getElevationAtIndices(int latitudeIndex, int longitudeIndex); /** Interpolate elevation. * <p> @@ -257,10 +252,8 @@ public interface Tile extends UpdatableTile { * @param latitude ground point latitude * @param longitude ground point longitude * @return interpolated elevation - * @exception RuggedException if point is farthest from the tile than the tolerance */ - double interpolateElevation(double latitude, double longitude) - throws RuggedException; + double interpolateElevation(double latitude, double longitude); /** Find the intersection of a line-of-sight and a Digital Elevation Model cell. * @param p point on the line @@ -270,11 +263,9 @@ public interface Tile extends UpdatableTile { * @param longitudeIndex longitude index of the Digital Elevation Model cell * @return point corresponding to line-of-sight crossing the Digital Elevation Model surface * if it lies within the cell, null otherwise - * @exception RuggedException if intersection point cannot be computed */ NormalizedGeodeticPoint cellIntersection(GeodeticPoint p, Vector3D los, - int latitudeIndex, int longitudeIndex) - throws RuggedException; + int latitudeIndex, int longitudeIndex); /** Check if a tile covers a ground point. * @param latitude ground point latitude diff --git a/src/main/java/org/orekit/rugged/raster/TileUpdater.java b/src/main/java/org/orekit/rugged/raster/TileUpdater.java index c76c96a8e138fa53bc4a3efb996a087201f8202c..089a08853f3e7cddd9b05b6a16acfe1f18b72a71 100644 --- a/src/main/java/org/orekit/rugged/raster/TileUpdater.java +++ b/src/main/java/org/orekit/rugged/raster/TileUpdater.java @@ -16,8 +16,6 @@ */ package org.orekit.rugged.raster; -import org.orekit.rugged.errors.RuggedException; - /** Interface used to update Digital Elevation Model tiles. * <p> * Implementations of this interface are must be provided by @@ -80,9 +78,7 @@ public interface TileUpdater { * @param latitude latitude that must be covered by the tile (rad) * @param longitude longitude that must be covered by the tile (rad) * @param tile to update - * @exception RuggedException if tile cannot be updated */ - void updateTile(double latitude, double longitude, UpdatableTile tile) - throws RuggedException; + void updateTile(double latitude, double longitude, UpdatableTile tile); } diff --git a/src/main/java/org/orekit/rugged/raster/TilesCache.java b/src/main/java/org/orekit/rugged/raster/TilesCache.java index 11712412ffd77cb867ad05b306b74fa750f0fbde..c970779d4aedb0708997e5c463ea84a01f863b22 100644 --- a/src/main/java/org/orekit/rugged/raster/TilesCache.java +++ b/src/main/java/org/orekit/rugged/raster/TilesCache.java @@ -57,10 +57,8 @@ public class TilesCache<T extends Tile> { * @param latitude ground point latitude * @param longitude ground point longitude * @return tile covering the ground point - * @exception RuggedException if newly created tile cannot be updated */ - public T getTile(final double latitude, final double longitude) - throws RuggedException { + public T getTile(final double latitude, final double longitude) { for (int i = 0; i < tiles.length; ++i) { final T tile = tiles[i]; diff --git a/src/main/java/org/orekit/rugged/raster/UpdatableTile.java b/src/main/java/org/orekit/rugged/raster/UpdatableTile.java index 606aec1b744a98580d878e8db8d3698223f1afa5..4f5dbc9b38af4dc67abab380f145bef3a46c08da 100644 --- a/src/main/java/org/orekit/rugged/raster/UpdatableTile.java +++ b/src/main/java/org/orekit/rugged/raster/UpdatableTile.java @@ -16,8 +16,6 @@ */ package org.orekit.rugged.raster; -import org.orekit.rugged.errors.RuggedException; - /** Interface representing one tile of a raster Digital Elevation Model. * @author Luc Maisonobe * @author Guylaine Prat @@ -31,12 +29,10 @@ public interface UpdatableTile { * @param longitudeStep step in longitude (size of one raster element) (rad) * @param latitudeRows number of latitude rows * @param longitudeColumns number of longitude columns - * @exception RuggedException if tile is empty (zero rows or columns) */ void setGeometry(double minLatitude, double minLongitude, double latitudeStep, double longitudeStep, - int latitudeRows, int longitudeColumns) - throws RuggedException; + int latitudeRows, int longitudeColumns); /** Set the elevation for one raster element. * <p> @@ -52,9 +48,7 @@ public interface UpdatableTile { * @param latitudeIndex index of latitude (row index) * @param longitudeIndex index of longitude (column index) * @param elevation elevation (m) - * @exception RuggedException if indices are out of bound */ - void setElevation(int latitudeIndex, int longitudeIndex, double elevation) - throws RuggedException; + void setElevation(int latitudeIndex, int longitudeIndex, double elevation); } diff --git a/src/main/java/org/orekit/rugged/refraction/AtmosphericComputationParameters.java b/src/main/java/org/orekit/rugged/refraction/AtmosphericComputationParameters.java index 0ca61c4d0aa39c6a6234672abbf39112c2b4deb6..257eec8b238b7b8981819d1dca1cb41ec5b22205 100644 --- a/src/main/java/org/orekit/rugged/refraction/AtmosphericComputationParameters.java +++ b/src/main/java/org/orekit/rugged/refraction/AtmosphericComputationParameters.java @@ -74,9 +74,8 @@ public class AtmosphericComputationParameters { * @param sensor line sensor * @param minLine min line defined for the inverse location * @param maxLine max line defined for the inverse location - * @throws RuggedException if invalid range for lines */ - public void configureCorrectionGrid(final LineSensor sensor, final int minLine, final int maxLine) throws RuggedException { + public void configureCorrectionGrid(final LineSensor sensor, final int minLine, final int maxLine) { // Keep information about the sensor and the required search lines. // Needed to test if the grid is initialized with this context. @@ -110,9 +109,8 @@ public class AtmosphericComputationParameters { * Overwrite the default values, for time optimization if necessary. * @param gridPixelStep grid pixel step for the inverse location computation * @param gridLineStep grid line step for the inverse location computation - * @throws RuggedException if invalid steps */ - public void setGridSteps(final int gridPixelStep, final int gridLineStep) throws RuggedException { + public void setGridSteps(final int gridPixelStep, final int gridLineStep) { if (gridPixelStep <= 0) { final String reason = " pixelStep <= 0"; diff --git a/src/main/java/org/orekit/rugged/refraction/AtmosphericRefraction.java b/src/main/java/org/orekit/rugged/refraction/AtmosphericRefraction.java index 961db64f65087e2ef0f5940f8e7c2713b4f67598..af4ea0bf07ef81136e4fc847f34d1bef50a18f6d 100644 --- a/src/main/java/org/orekit/rugged/refraction/AtmosphericRefraction.java +++ b/src/main/java/org/orekit/rugged/refraction/AtmosphericRefraction.java @@ -74,13 +74,11 @@ public abstract class AtmosphericRefraction { * @param rawIntersection intersection point before refraction correction * @param algorithm intersection algorithm * @return corrected point with the effect of atmospheric refraction - * @throws RuggedException if there is no refraction data at altitude of rawIntersection or see * {@link org.orekit.rugged.utils.ExtendedEllipsoid#pointAtAltitude(Vector3D, Vector3D, double)} or see * {@link org.orekit.rugged.intersection.IntersectionAlgorithm#refineIntersection(org.orekit.rugged.utils.ExtendedEllipsoid, Vector3D, Vector3D, NormalizedGeodeticPoint)} */ public abstract NormalizedGeodeticPoint applyCorrection(Vector3D satPos, Vector3D satLos, NormalizedGeodeticPoint rawIntersection, - IntersectionAlgorithm algorithm) - throws RuggedException; + IntersectionAlgorithm algorithm); /** Apply correction to the intersected point with an atmospheric refraction model, * using a time optimized algorithm. @@ -91,15 +89,13 @@ public abstract class AtmosphericRefraction { * @param rawIntersection intersection point before refraction correction * @param algorithm intersection algorithm * @return corrected point with the effect of atmospheric refraction - * @throws RuggedException if there is no refraction data at altitude of rawIntersection or see * {@link org.orekit.rugged.utils.ExtendedEllipsoid#pointAtAltitude(Vector3D, Vector3D, double)} or see * {@link org.orekit.rugged.intersection.IntersectionAlgorithm#refineIntersection(org.orekit.rugged.utils.ExtendedEllipsoid, Vector3D, Vector3D, NormalizedGeodeticPoint)} * @since 3.0 */ public abstract NormalizedGeodeticPoint applyCorrection(LineSensor lineSensor, SensorPixel sensorPixel, Vector3D satPos, Vector3D satLos, NormalizedGeodeticPoint rawIntersection, - IntersectionAlgorithm algorithm) - throws RuggedException; + IntersectionAlgorithm algorithm); /** Deactivate computation (needed for the inverse location computation). * @since 3.0 @@ -136,9 +132,8 @@ public abstract class AtmosphericRefraction { * @param sensor line sensor * @param minLine min line defined for the inverse location * @param maxLine max line defined for the inverse location - * @throws RuggedException if invalid range for lines */ - public void configureCorrectionGrid(final LineSensor sensor, final int minLine, final int maxLine) throws RuggedException { + public void configureCorrectionGrid(final LineSensor sensor, final int minLine, final int maxLine) { atmosphericParams.configureCorrectionGrid(sensor, minLine, maxLine); } @@ -167,9 +162,8 @@ public abstract class AtmosphericRefraction { * Overwrite the default values, for time optimization for instance. * @param pixelStep pixel step for the inverse location computation * @param lineStep line step for the inverse location computation - * @throws RuggedException if invalid steps */ - public void setGridSteps(final int pixelStep, final int lineStep) throws RuggedException { + public void setGridSteps(final int pixelStep, final int lineStep) { atmosphericParams.setGridSteps(pixelStep, lineStep); } @@ -180,9 +174,8 @@ public abstract class AtmosphericRefraction { * The bilinear interpolating functions are then computed for pixel and for line. * Need to be computed only once for a given sensor with the same minLine and maxLine. * @param sensorPixelGridInverseWithout inverse location grid WITHOUT atmospheric refraction - * @throws RuggedException if invalid range for lines */ - public void computeGridCorrectionFunctions(final SensorPixel[][] sensorPixelGridInverseWithout) throws RuggedException { + public void computeGridCorrectionFunctions(final SensorPixel[][] sensorPixelGridInverseWithout) { // Compute for a sensor grid, the associated ground grid, WITH atmospheric effect // (for interpolations we need a regular grid) diff --git a/src/main/java/org/orekit/rugged/refraction/MultiLayerModel.java b/src/main/java/org/orekit/rugged/refraction/MultiLayerModel.java index db8bd800f1b2905fa01c4ca217ab6ad1f5cbeedc..7b8b7f1463ab132a273842b2dece9be13bf49584 100644 --- a/src/main/java/org/orekit/rugged/refraction/MultiLayerModel.java +++ b/src/main/java/org/orekit/rugged/refraction/MultiLayerModel.java @@ -54,9 +54,8 @@ public class MultiLayerModel extends AtmosphericRefraction { * This model uses a built-in set of layers. * </p> * @param ellipsoid the ellipsoid to be used. - * @throws RuggedException if problem at layers construction */ - public MultiLayerModel(final ExtendedEllipsoid ellipsoid) throws RuggedException { + public MultiLayerModel(final ExtendedEllipsoid ellipsoid) { super(); @@ -86,10 +85,8 @@ public class MultiLayerModel extends AtmosphericRefraction { /** Simple constructor. * @param ellipsoid the ellipsoid to be used. * @param refractionLayers the refraction layers to be used with this model (layers can be in any order). - * @throws RuggedException if problem at layers construction */ - public MultiLayerModel(final ExtendedEllipsoid ellipsoid, final List<ConstantRefractionLayer> refractionLayers) - throws RuggedException { + public MultiLayerModel(final ExtendedEllipsoid ellipsoid, final List<ConstantRefractionLayer> refractionLayers) { super(); // at this stage no optimization is set up: no optimization grid is defined @@ -110,12 +107,11 @@ public class MultiLayerModel extends AtmosphericRefraction { * @param satLos satellite line of sight, in body frame * @param rawIntersection intersection point without refraction correction * @return the intersection position and LOS with the lowest atmospheric layer - * @throws RuggedException if no layer data at asked altitude * @since 3.0 */ private IntersectionLOS computeToLowestAtmosphereLayer( final Vector3D satPos, final Vector3D satLos, - final NormalizedGeodeticPoint rawIntersection) throws RuggedException { + final NormalizedGeodeticPoint rawIntersection) { if (rawIntersection.getAltitude() < atmosphereLowestAltitude) { throw new RuggedException(RuggedMessages.NO_LAYER_DATA, rawIntersection.getAltitude(), @@ -241,7 +237,7 @@ public class MultiLayerModel extends AtmosphericRefraction { public NormalizedGeodeticPoint applyCorrection(final Vector3D satPos, final Vector3D satLos, final NormalizedGeodeticPoint rawIntersection, final IntersectionAlgorithm algorithm) - throws RuggedException { + { final IntersectionLOS intersectionLOS = computeToLowestAtmosphereLayer(satPos, satLos, rawIntersection); final Vector3D pos = intersectionLOS.getIntersectionPos(); @@ -258,8 +254,7 @@ public class MultiLayerModel extends AtmosphericRefraction { public NormalizedGeodeticPoint applyCorrection(final LineSensor lineSensor, final SensorPixel sensorPixel, final Vector3D satPos, final Vector3D satLos, final NormalizedGeodeticPoint rawIntersection, - final IntersectionAlgorithm algorithm) - throws RuggedException { + final IntersectionAlgorithm algorithm) { // TODO to be done throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "Atmospheric optimization for direct loc"); diff --git a/src/main/java/org/orekit/rugged/utils/ExtendedEllipsoid.java b/src/main/java/org/orekit/rugged/utils/ExtendedEllipsoid.java index 3324e0ad27f484055c5392090a4e4ec061443daf..c95060af412879694c41f11dc8904cd92700bb81 100644 --- a/src/main/java/org/orekit/rugged/utils/ExtendedEllipsoid.java +++ b/src/main/java/org/orekit/rugged/utils/ExtendedEllipsoid.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -22,7 +22,6 @@ import org.hipparchus.util.FastMath; import org.hipparchus.util.MathArrays; import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; -import org.orekit.errors.OrekitException; import org.orekit.frames.Frame; import org.orekit.rugged.errors.DumpManager; import org.orekit.rugged.errors.RuggedException; @@ -68,8 +67,7 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { /** {@inheritDoc} */ @Override - public GeodeticPoint transform(final Vector3D point, final Frame frame, final AbsoluteDate date) - throws OrekitException { + public GeodeticPoint transform(final Vector3D point, final Frame frame, final AbsoluteDate date) { DumpManager.dumpEllipsoid(this); return super.transform(point, frame, date); } @@ -82,11 +80,9 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * when there are two points at the desired latitude along the line, it should * be close to los surface intersection (m) * @return point at latitude (m) - * @exception RuggedException if no such point exists */ public Vector3D pointAtLatitude(final Vector3D position, final Vector3D los, - final double latitude, final Vector3D closeReference) - throws RuggedException { + final double latitude, final Vector3D closeReference) { DumpManager.dumpEllipsoid(this); @@ -165,10 +161,8 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * @param los pixel line-of-sight, not necessarily normalized (in body frame) * @param longitude longitude with respect to ellipsoid (rad) * @return point at longitude (m) - * @exception RuggedException if no such point exists */ - public Vector3D pointAtLongitude(final Vector3D position, final Vector3D los, final double longitude) - throws RuggedException { + public Vector3D pointAtLongitude(final Vector3D position, final Vector3D los, final double longitude) { DumpManager.dumpEllipsoid(this); @@ -191,24 +185,19 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * @param centralLongitude reference longitude lc such that the point longitude will * be normalized between lc-π and lc+π (rad) * @return point on ground - * @exception RuggedException if no such point exists (typically line-of-sight missing body) */ public NormalizedGeodeticPoint pointOnGround(final Vector3D position, final Vector3D los, - final double centralLongitude) - throws RuggedException { - try { - DumpManager.dumpEllipsoid(this); - final GeodeticPoint gp = - getIntersectionPoint(new Line(position, new Vector3D(1, position, 1e6, los), 1.0e-12), - position, getBodyFrame(), null); - if (gp == null) { - throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_DOES_NOT_REACH_GROUND); - } - return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), - centralLongitude); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); + final double centralLongitude) { + + DumpManager.dumpEllipsoid(this); + final GeodeticPoint gp = + getIntersectionPoint(new Line(position, new Vector3D(1, position, 1e6, los), 1.0e-12), + position, getBodyFrame(), null); + if (gp == null) { + throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_DOES_NOT_REACH_GROUND); } + return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), + centralLongitude); } /** Get point at some altitude along a pixel line of sight. @@ -216,55 +205,47 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * @param los pixel line-of-sight, not necessarily normalized (in body frame) * @param altitude altitude with respect to ellipsoid (m) * @return point at altitude (m) - * @exception RuggedException if no such point exists (typically too negative altitude) */ - public Vector3D pointAtAltitude(final Vector3D position, final Vector3D los, final double altitude) - throws RuggedException { - try { - - DumpManager.dumpEllipsoid(this); - - // point on line closest to origin - final double los2 = los.getNormSq(); - final double dot = Vector3D.dotProduct(position, los); - final double k0 = -dot / los2; - final Vector3D close0 = new Vector3D(1, position, k0, los); - - // very rough guess: if body is spherical, the desired point on line - // is at distance ae + altitude from origin - final double r = getEquatorialRadius() + altitude; - final double delta2 = r * r - close0.getNormSq(); - if (delta2 < 0) { - throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_NEVER_CROSSES_ALTITUDE, altitude); - } - final double deltaK = FastMath.sqrt(delta2 / los2); - final double k1 = k0 + deltaK; - final double k2 = k0 - deltaK; - double k = (FastMath.abs(k1) <= FastMath.abs(k2)) ? k1 : k2; + public Vector3D pointAtAltitude(final Vector3D position, final Vector3D los, final double altitude) { - // this loop generally converges in 3 iterations - for (int i = 0; i < 100; ++i) { - - final Vector3D point = new Vector3D(1, position, k, los); - final GeodeticPoint gpK = transform(point, getBodyFrame(), null); - final double deltaH = altitude - gpK.getAltitude(); - if (FastMath.abs(deltaH) <= ALTITUDE_CONVERGENCE) { - return point; - } - - // improve the offset using linear ratio between - // altitude variation and displacement along line-of-sight - k += deltaH / Vector3D.dotProduct(gpK.getZenith(), los); + DumpManager.dumpEllipsoid(this); + // point on line closest to origin + final double los2 = los.getNormSq(); + final double dot = Vector3D.dotProduct(position, los); + final double k0 = -dot / los2; + final Vector3D close0 = new Vector3D(1, position, k0, los); + + // very rough guess: if body is spherical, the desired point on line + // is at distance ae + altitude from origin + final double r = getEquatorialRadius() + altitude; + final double delta2 = r * r - close0.getNormSq(); + if (delta2 < 0) { + throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_NEVER_CROSSES_ALTITUDE, altitude); + } + final double deltaK = FastMath.sqrt(delta2 / los2); + final double k1 = k0 + deltaK; + final double k2 = k0 - deltaK; + double k = (FastMath.abs(k1) <= FastMath.abs(k2)) ? k1 : k2; + + // this loop generally converges in 3 iterations + for (int i = 0; i < 100; ++i) { + + final Vector3D point = new Vector3D(1, position, k, los); + final GeodeticPoint gpK = transform(point, getBodyFrame(), null); + final double deltaH = altitude - gpK.getAltitude(); + if (FastMath.abs(deltaH) <= ALTITUDE_CONVERGENCE) { + return point; } - // this should never happen - throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_NEVER_CROSSES_ALTITUDE, altitude); + // improve the offset using linear ratio between + // altitude variation and displacement along line-of-sight + k += deltaH / Vector3D.dotProduct(gpK.getZenith(), los); - } catch (OrekitException oe) { - // this should never happen - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); } + + // this should never happen + throw new RuggedException(RuggedMessages.LINE_OF_SIGHT_NEVER_CROSSES_ALTITUDE, altitude); } /** Convert a line-of-sight from Cartesian to topocentric. @@ -302,22 +283,15 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * with respect to the primary point (in body frame and Cartesian coordinates) * @return line-of-sight in topocentric frame (East, North, Zenith) of the point, * scaled to match radians in the horizontal plane and meters along the vertical axis - * @exception RuggedException if points cannot be converted to geodetic coordinates */ - public Vector3D convertLos(final Vector3D primary, final Vector3D secondary) - throws RuggedException { - try { - - // switch to geodetic coordinates using primary point as reference - final GeodeticPoint point = transform(primary, getBodyFrame(), null); - final Vector3D los = secondary.subtract(primary); + public Vector3D convertLos(final Vector3D primary, final Vector3D secondary) { - // convert line of sight - return convertLos(point, los); + // switch to geodetic coordinates using primary point as reference + final GeodeticPoint point = transform(primary, getBodyFrame(), null); + final Vector3D los = secondary.subtract(primary); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); - } + // convert line of sight + return convertLos(point, los); } /** Transform a cartesian point to a surface-relative point. @@ -327,11 +301,9 @@ public class ExtendedEllipsoid extends OneAxisEllipsoid { * @param centralLongitude reference longitude lc such that the point longitude will * be normalized between lc-π and lc+π (rad) * @return point at the same location but as a surface-relative point - * @exception OrekitException if point cannot be converted to body frame */ public NormalizedGeodeticPoint transform(final Vector3D point, final Frame frame, final AbsoluteDate date, - final double centralLongitude) - throws OrekitException { + final double centralLongitude) { final GeodeticPoint gp = transform(point, frame, date); return new NormalizedGeodeticPoint(gp.getLatitude(), gp.getLongitude(), gp.getAltitude(), centralLongitude); diff --git a/src/main/java/org/orekit/rugged/utils/RoughVisibilityEstimator.java b/src/main/java/org/orekit/rugged/utils/RoughVisibilityEstimator.java index 300ab31de5ed20c9f0246dc67cac82d5acdba952..a47cf4c55b230ed0f06ea9d6026c916ca87925cd 100644 --- a/src/main/java/org/orekit/rugged/utils/RoughVisibilityEstimator.java +++ b/src/main/java/org/orekit/rugged/utils/RoughVisibilityEstimator.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -16,14 +16,13 @@ */ package org.orekit.rugged.utils; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.util.FastMath; import java.util.ArrayList; import java.util.List; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; -import org.orekit.errors.OrekitException; import org.orekit.frames.Frame; import org.orekit.frames.Transform; import org.orekit.time.AbsoluteDate; @@ -64,11 +63,9 @@ public class RoughVisibilityEstimator { * @param ellipsoid ground ellipsoid * @param frame frame in which position and velocity are defined (may be inertial or body frame) * @param positionsVelocities satellite position and velocity (m and m/s in specified frame) - * @exception OrekitException if position-velocity cannot be converted to body frame */ public RoughVisibilityEstimator(final OneAxisEllipsoid ellipsoid, final Frame frame, - final List<TimeStampedPVCoordinates> positionsVelocities) - throws OrekitException { + final List<TimeStampedPVCoordinates> positionsVelocities) { this.ellipsoid = ellipsoid; diff --git a/src/main/java/org/orekit/rugged/utils/SpacecraftToObservedBody.java b/src/main/java/org/orekit/rugged/utils/SpacecraftToObservedBody.java index 75ef62129ec5e3684e1cf200dbda1d5ceaa5fb5e..3d4c61ba5da51e488c75655998db0ac7b52246d6 100644 --- a/src/main/java/org/orekit/rugged/utils/SpacecraftToObservedBody.java +++ b/src/main/java/org/orekit/rugged/utils/SpacecraftToObservedBody.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -16,13 +16,12 @@ */ package org.orekit.rugged.utils; -import org.hipparchus.util.FastMath; import java.io.Serializable; import java.util.ArrayList; import java.util.List; import java.util.stream.Collectors; -import org.orekit.errors.OrekitException; +import org.hipparchus.util.FastMath; import org.orekit.frames.Frame; import org.orekit.frames.Transform; import org.orekit.rugged.errors.DumpManager; @@ -86,9 +85,6 @@ public class SpacecraftToObservedBody implements Serializable { * @param quaternions satellite quaternions * @param aInterpolationNumber number of points to use for attitude interpolation * @param aFilter filter for derivatives from the sample to use in attitude interpolation - * @exception RuggedException if [{@code minDate}, {@code maxDate}] search time span overshoots - * position or attitude samples by more than {@code overshootTolerance} - * , */ public SpacecraftToObservedBody(final Frame inertialFrame, final Frame bodyFrame, final AbsoluteDate minDate, final AbsoluteDate maxDate, final double tStep, @@ -96,92 +92,86 @@ public class SpacecraftToObservedBody implements Serializable { final List<TimeStampedPVCoordinates> positionsVelocities, final int pvInterpolationNumber, final CartesianDerivativesFilter pvFilter, final List<TimeStampedAngularCoordinates> quaternions, final int aInterpolationNumber, - final AngularDerivativesFilter aFilter) - throws RuggedException { - try { - - this.inertialFrame = inertialFrame; - this.bodyFrame = bodyFrame; - this.minDate = minDate; - this.maxDate = maxDate; - this.overshootTolerance = overshootTolerance; - - // safety checks - final AbsoluteDate minPVDate = positionsVelocities.get(0).getDate(); - final AbsoluteDate maxPVDate = positionsVelocities.get(positionsVelocities.size() - 1).getDate(); - if (minPVDate.durationFrom(minDate) > overshootTolerance) { - throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, minDate, minPVDate, maxPVDate); - } - if (maxDate.durationFrom(maxPVDate) > overshootTolerance) { - throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, maxDate, minPVDate, maxPVDate); - } + final AngularDerivativesFilter aFilter) { - final AbsoluteDate minQDate = quaternions.get(0).getDate(); - final AbsoluteDate maxQDate = quaternions.get(quaternions.size() - 1).getDate(); - if (minQDate.durationFrom(minDate) > overshootTolerance) { - throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, minDate, minQDate, maxQDate); - } - if (maxDate.durationFrom(maxQDate) > overshootTolerance) { - throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, maxDate, minQDate, maxQDate); - } + this.inertialFrame = inertialFrame; + this.bodyFrame = bodyFrame; + this.minDate = minDate; + this.maxDate = maxDate; + this.overshootTolerance = overshootTolerance; - // set up the cache for position-velocities - final TimeStampedCache<TimeStampedPVCoordinates> pvCache = - new ImmutableTimeStampedCache<TimeStampedPVCoordinates>(pvInterpolationNumber, positionsVelocities); - - // set up the cache for attitudes - final TimeStampedCache<TimeStampedAngularCoordinates> aCache = - new ImmutableTimeStampedCache<TimeStampedAngularCoordinates>(aInterpolationNumber, quaternions); - - final int n = (int) FastMath.ceil(maxDate.durationFrom(minDate) / tStep); - this.tStep = tStep; - this.bodyToInertial = new ArrayList<Transform>(n); - this.inertialToBody = new ArrayList<Transform>(n); - this.scToInertial = new ArrayList<Transform>(n); - for (AbsoluteDate date = minDate; bodyToInertial.size() < n; date = date.shiftedBy(tStep)) { - - // interpolate position-velocity, allowing slight extrapolation near the boundaries - final AbsoluteDate pvInterpolationDate; - if (date.compareTo(pvCache.getEarliest().getDate()) < 0) { - pvInterpolationDate = pvCache.getEarliest().getDate(); - } else if (date.compareTo(pvCache.getLatest().getDate()) > 0) { - pvInterpolationDate = pvCache.getLatest().getDate(); - } else { - pvInterpolationDate = date; - } - final TimeStampedPVCoordinates interpolatedPV = - TimeStampedPVCoordinates.interpolate(pvInterpolationDate, pvFilter, - pvCache.getNeighbors(pvInterpolationDate)); - final TimeStampedPVCoordinates pv = interpolatedPV.shiftedBy(date.durationFrom(pvInterpolationDate)); - - // interpolate attitude, allowing slight extrapolation near the boundaries - final AbsoluteDate aInterpolationDate; - if (date.compareTo(aCache.getEarliest().getDate()) < 0) { - aInterpolationDate = aCache.getEarliest().getDate(); - } else if (date.compareTo(aCache.getLatest().getDate()) > 0) { - aInterpolationDate = aCache.getLatest().getDate(); - } else { - aInterpolationDate = date; - } - final TimeStampedAngularCoordinates interpolatedQuaternion = - TimeStampedAngularCoordinates.interpolate(aInterpolationDate, aFilter, - aCache.getNeighbors(aInterpolationDate).collect(Collectors.toList())); - final TimeStampedAngularCoordinates quaternion = interpolatedQuaternion.shiftedBy(date.durationFrom(aInterpolationDate)); - - // store transform from spacecraft frame to inertial frame - scToInertial.add(new Transform(date, - new Transform(date, quaternion.revert()), - new Transform(date, pv))); - - // store transform from body frame to inertial frame - final Transform b2i = bodyFrame.getTransformTo(inertialFrame, date); - bodyToInertial.add(b2i); - inertialToBody.add(b2i.getInverse()); + // safety checks + final AbsoluteDate minPVDate = positionsVelocities.get(0).getDate(); + final AbsoluteDate maxPVDate = positionsVelocities.get(positionsVelocities.size() - 1).getDate(); + if (minPVDate.durationFrom(minDate) > overshootTolerance) { + throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, minDate, minPVDate, maxPVDate); + } + if (maxDate.durationFrom(maxPVDate) > overshootTolerance) { + throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, maxDate, minPVDate, maxPVDate); + } + final AbsoluteDate minQDate = quaternions.get(0).getDate(); + final AbsoluteDate maxQDate = quaternions.get(quaternions.size() - 1).getDate(); + if (minQDate.durationFrom(minDate) > overshootTolerance) { + throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, minDate, minQDate, maxQDate); + } + if (maxDate.durationFrom(maxQDate) > overshootTolerance) { + throw new RuggedException(RuggedMessages.OUT_OF_TIME_RANGE, maxDate, minQDate, maxQDate); + } + + // set up the cache for position-velocities + final TimeStampedCache<TimeStampedPVCoordinates> pvCache = + new ImmutableTimeStampedCache<TimeStampedPVCoordinates>(pvInterpolationNumber, positionsVelocities); + + // set up the cache for attitudes + final TimeStampedCache<TimeStampedAngularCoordinates> aCache = + new ImmutableTimeStampedCache<TimeStampedAngularCoordinates>(aInterpolationNumber, quaternions); + + final int n = (int) FastMath.ceil(maxDate.durationFrom(minDate) / tStep); + this.tStep = tStep; + this.bodyToInertial = new ArrayList<Transform>(n); + this.inertialToBody = new ArrayList<Transform>(n); + this.scToInertial = new ArrayList<Transform>(n); + for (AbsoluteDate date = minDate; bodyToInertial.size() < n; date = date.shiftedBy(tStep)) { + + // interpolate position-velocity, allowing slight extrapolation near the boundaries + final AbsoluteDate pvInterpolationDate; + if (date.compareTo(pvCache.getEarliest().getDate()) < 0) { + pvInterpolationDate = pvCache.getEarliest().getDate(); + } else if (date.compareTo(pvCache.getLatest().getDate()) > 0) { + pvInterpolationDate = pvCache.getLatest().getDate(); + } else { + pvInterpolationDate = date; } + final TimeStampedPVCoordinates interpolatedPV = + TimeStampedPVCoordinates.interpolate(pvInterpolationDate, pvFilter, + pvCache.getNeighbors(pvInterpolationDate)); + final TimeStampedPVCoordinates pv = interpolatedPV.shiftedBy(date.durationFrom(pvInterpolationDate)); + + // interpolate attitude, allowing slight extrapolation near the boundaries + final AbsoluteDate aInterpolationDate; + if (date.compareTo(aCache.getEarliest().getDate()) < 0) { + aInterpolationDate = aCache.getEarliest().getDate(); + } else if (date.compareTo(aCache.getLatest().getDate()) > 0) { + aInterpolationDate = aCache.getLatest().getDate(); + } else { + aInterpolationDate = date; + } + final TimeStampedAngularCoordinates interpolatedQuaternion = + TimeStampedAngularCoordinates.interpolate(aInterpolationDate, aFilter, + aCache.getNeighbors(aInterpolationDate).collect(Collectors.toList())); + final TimeStampedAngularCoordinates quaternion = interpolatedQuaternion.shiftedBy(date.durationFrom(aInterpolationDate)); + + // store transform from spacecraft frame to inertial frame + scToInertial.add(new Transform(date, + new Transform(date, quaternion.revert()), + new Transform(date, pv))); + + // store transform from body frame to inertial frame + final Transform b2i = bodyFrame.getTransformTo(inertialFrame, date); + bodyToInertial.add(b2i); + inertialToBody.add(b2i.getInverse()); - } catch (OrekitException oe) { - throw new RuggedException(oe, oe.getSpecifier(), oe.getParts()); } } @@ -262,30 +252,24 @@ public class SpacecraftToObservedBody implements Serializable { /** Get transform from spacecraft to inertial frame. * @param date date of the transform * @return transform from spacecraft to inertial frame - * @exception RuggedException if frames cannot be computed at date */ - public Transform getScToInertial(final AbsoluteDate date) - throws RuggedException { + public Transform getScToInertial(final AbsoluteDate date) { return interpolate(date, scToInertial); } /** 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 interpolate(date, inertialToBody); } /** 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 interpolate(date, bodyToInertial); } @@ -293,10 +277,8 @@ public class SpacecraftToObservedBody implements Serializable { * @param date date of the transform * @param list transforms list to interpolate from * @return interpolated transform - * @exception RuggedException if frames cannot be computed at date */ - private Transform interpolate(final AbsoluteDate date, final List<Transform> list) - throws RuggedException { + private Transform interpolate(final AbsoluteDate date, final List<Transform> list) { // check date range if (!isInRange(date)) { diff --git a/src/test/java/org/orekit/rugged/TestUtils.java b/src/test/java/org/orekit/rugged/TestUtils.java index d67cb3e20b2a718671c2eeb84a4898c5757b2b6e..fbef4fc39c451a0a7dee6a71c5f84b7b592ee314 100644 --- a/src/test/java/org/orekit/rugged/TestUtils.java +++ b/src/test/java/org/orekit/rugged/TestUtils.java @@ -17,13 +17,6 @@ package org.orekit.rugged; -import org.hipparchus.geometry.euclidean.threed.Rotation; -import org.hipparchus.geometry.euclidean.threed.RotationConvention; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; -import org.hipparchus.util.FastMath; -import org.junit.Assert; - import static org.junit.Assert.assertEquals; import java.lang.reflect.Field; @@ -32,6 +25,12 @@ import java.util.ArrayList; import java.util.List; import java.util.Map; +import org.hipparchus.geometry.euclidean.threed.Rotation; +import org.hipparchus.geometry.euclidean.threed.RotationConvention; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; +import org.hipparchus.util.FastMath; +import org.junit.Assert; import org.orekit.attitudes.AttitudeProvider; import org.orekit.attitudes.NadirPointing; import org.orekit.attitudes.YawCompensation; @@ -40,7 +39,6 @@ import org.orekit.bodies.CelestialBodyFactory; import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; import org.orekit.data.DataProvidersManager; -import org.orekit.errors.OrekitException; import org.orekit.forces.gravity.HolmesFeatherstoneAttractionModel; import org.orekit.forces.gravity.ThirdBodyAttraction; import org.orekit.forces.gravity.potential.GravityFieldFactory; @@ -159,8 +157,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 +183,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 +193,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 +202,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 +228,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 +293,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 +316,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/adjustment/AdjustmentContextTest.java b/src/test/java/org/orekit/rugged/adjustment/AdjustmentContextTest.java index e897ecdf4e08657aa84d51c6770ffd85af56a827..f7dd7482390a818f4e373bf932c329ec84f03558 100644 --- a/src/test/java/org/orekit/rugged/adjustment/AdjustmentContextTest.java +++ b/src/test/java/org/orekit/rugged/adjustment/AdjustmentContextTest.java @@ -62,7 +62,7 @@ public class AdjustmentContextTest { } @Test - public void testAdjustmentContext() throws RuggedException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { + public void testAdjustmentContext() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements); @@ -86,7 +86,7 @@ public class AdjustmentContextTest { } @Test - public void testEstimateFreeParameters() throws RuggedException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { + public void testEstimateFreeParameters() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements); diff --git a/src/test/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilderTest.java b/src/test/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilderTest.java index 00e50fab525e8d7ec374733a73a9089ce0f93c76..be7ad216ab106c087b5f667347871894ea5b57a0 100644 --- a/src/test/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilderTest.java +++ b/src/test/java/org/orekit/rugged/adjustment/GroundOptimizationProblemBuilderTest.java @@ -1,7 +1,6 @@ package org.orekit.rugged.adjustment; import java.lang.reflect.Field; - import java.util.ArrayList; import java.util.Collection; import java.util.Collections; @@ -11,14 +10,11 @@ import java.util.Map.Entry; import java.util.Set; import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum; - import org.junit.After; import org.junit.Assert; import org.junit.Before; import org.junit.Test; - import org.orekit.bodies.GeodeticPoint; -import org.orekit.errors.OrekitException; import org.orekit.rugged.TestUtils; import org.orekit.rugged.adjustment.measurements.Observables; import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; @@ -53,7 +49,7 @@ public class GroundOptimizationProblemBuilderTest { } @Test - public void testEstimateFreeParameters() throws RuggedException { + public void testEstimateFreeParameters() { AdjustmentContext adjustmentContext = new AdjustmentContext(Collections.singletonList(rugged), measurements); final int maxIterations = 50; @@ -88,7 +84,7 @@ public class GroundOptimizationProblemBuilderTest { } @Test - public void testNoParametersSelected() throws RuggedException, OrekitException { + public void testNoParametersSelected() { try { RefiningParametersDriver.unselectRoll(rugged, sensorName); RefiningParametersDriver.unselectPitch(rugged, sensorName); @@ -131,7 +127,7 @@ public class GroundOptimizationProblemBuilderTest { } @Test - public void testDefaultRuggedName() throws RuggedException { + public void testDefaultRuggedName(){ // Get the measurements as computed in other tests Collection<SensorToGroundMapping> sensorToGroundMapping = measurements.getGroundMappings(); diff --git a/src/test/java/org/orekit/rugged/adjustment/InterSensorOptimizationProblemBuilderTest.java b/src/test/java/org/orekit/rugged/adjustment/InterSensorOptimizationProblemBuilderTest.java index 6018cda984fce7bbf8744b58ec690268abe060b1..5a56cc1f1b1826f43fe31156ee22d0ddc3a6e6fc 100644 --- a/src/test/java/org/orekit/rugged/adjustment/InterSensorOptimizationProblemBuilderTest.java +++ b/src/test/java/org/orekit/rugged/adjustment/InterSensorOptimizationProblemBuilderTest.java @@ -17,7 +17,6 @@ package org.orekit.rugged.adjustment; import java.lang.reflect.Field; - import java.util.ArrayList; import java.util.Collection; import java.util.Iterator; @@ -32,14 +31,12 @@ import org.junit.After; import org.junit.Assert; import org.junit.Before; import org.junit.Test; - import org.orekit.rugged.TestUtils; import org.orekit.rugged.adjustment.measurements.Observables; import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; import org.orekit.rugged.adjustment.util.InitInterRefiningTest; 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; @@ -66,7 +63,7 @@ public class InterSensorOptimizationProblemBuilderTest { } @Test - public void testEstimateFreeParameters() throws RuggedException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { + public void testEstimateFreeParameters() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements); @@ -108,7 +105,7 @@ public class InterSensorOptimizationProblemBuilderTest { } @Test - public void testEarthConstraintPostponed() throws RuggedException { + public void testEarthConstraintPostponed() { // Get the measurements as computed in other tests Collection<SensorToSensorMapping> sensorToSensorMapping = measurements.getInterMappings(); @@ -190,7 +187,7 @@ public class InterSensorOptimizationProblemBuilderTest { } @Test - public void testDefaultRuggedNames() throws RuggedException { + public void testDefaultRuggedNames() { // In that case there are no body distance set at construction @@ -286,7 +283,7 @@ public class InterSensorOptimizationProblemBuilderTest { } @Test - public void testInvalidRuggedNames() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException, RuggedException { + public void testInvalidRuggedNames() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { final int maxIterations = 120; final double convergenceThreshold = 1.e-7; @@ -314,8 +311,8 @@ public class InterSensorOptimizationProblemBuilderTest { adjuster.optimize(theProblem); Assert.fail("An exception should have been thrown"); - } catch (RuggedExceptionWrapper re) { - Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getException().getSpecifier()); + } catch (RuggedException re) { + Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getSpecifier()); } // Then set RuggedA to null to get the right exception ... @@ -329,8 +326,8 @@ public class InterSensorOptimizationProblemBuilderTest { adjuster.optimize(theProblem); Assert.fail("An exception should have been thrown"); - } catch (RuggedExceptionWrapper re) { - Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getException().getSpecifier()); + } catch (RuggedException re) { + Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getSpecifier()); } } diff --git a/src/test/java/org/orekit/rugged/adjustment/util/InitGroundRefiningTest.java b/src/test/java/org/orekit/rugged/adjustment/util/InitGroundRefiningTest.java index 4cdb8be5b29db937cb7fb7b9b247a13338c6ab65..ce0739a6403b752c939c8f6bb10f313c3b39751d 100644 --- a/src/test/java/org/orekit/rugged/adjustment/util/InitGroundRefiningTest.java +++ b/src/test/java/org/orekit/rugged/adjustment/util/InitGroundRefiningTest.java @@ -25,7 +25,6 @@ import org.orekit.rugged.api.EllipsoidId; import org.orekit.rugged.api.InertialFrameId; import org.orekit.rugged.api.Rugged; import org.orekit.rugged.api.RuggedBuilder; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.SensorPixel; import org.orekit.time.AbsoluteDate; @@ -65,9 +64,8 @@ public class InitGroundRefiningTest { /** * Initialize ground refining tests with default values for disruptions on sensors characteristics - * @throws RuggedException */ - public void initGroundRefiningTest() throws RuggedException { + public void initGroundRefiningTest() { initGroundRefiningTest(defaultRollDisruption, defaultPitchDisruption, defaultFactorDisruption); } @@ -76,9 +74,8 @@ public class InitGroundRefiningTest { * @param rollDisruption disruption to apply to roll angle for sensor (deg) * @param pitchDisruption disruption to apply to pitch angle for sensor (deg) * @param factorDisruption disruption to apply to homothety factor for sensor - * @throws RuggedException */ - public void initGroundRefiningTest(double rollDisruption, double pitchDisruption, double factorDisruption) throws RuggedException { + public void initGroundRefiningTest(double rollDisruption, double pitchDisruption, double factorDisruption) { try { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); @@ -177,9 +174,8 @@ public class InitGroundRefiningTest { * @param lineSampling line sampling * @param pixelSampling pixel sampling * @param flag to tell if the Rugged name used is the default one (true) or not (false) - * @throws RuggedException */ - public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, boolean defaultRuggedName) throws RuggedException { + public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, boolean defaultRuggedName) { // Generate reference mapping SensorToGroundMapping groundMapping; diff --git a/src/test/java/org/orekit/rugged/adjustment/util/InitInterRefiningTest.java b/src/test/java/org/orekit/rugged/adjustment/util/InitInterRefiningTest.java index 68bb5c96323d3e174ddcdc3561d96ee1b1ad4e09..ecb5679fbd4889df6b4c5a5388bdae216bca04f5 100644 --- a/src/test/java/org/orekit/rugged/adjustment/util/InitInterRefiningTest.java +++ b/src/test/java/org/orekit/rugged/adjustment/util/InitInterRefiningTest.java @@ -31,7 +31,6 @@ import org.orekit.rugged.api.EllipsoidId; import org.orekit.rugged.api.InertialFrameId; import org.orekit.rugged.api.Rugged; import org.orekit.rugged.api.RuggedBuilder; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.SensorPixel; import org.orekit.rugged.utils.DSGenerator; @@ -86,9 +85,8 @@ public class InitInterRefiningTest { /** * Initialize refining tests with default values for disruptions on sensors characteristics - * @throws RuggedException */ - public void initRefiningTest() throws RuggedException { + public void initRefiningTest() { initRefiningTest(defaultRollDisruptionA, defaultPitchDisruptionA, defaultFactorDisruptionA, defaultRollDisruptionB, defaultPitchDisruptionB); @@ -100,10 +98,9 @@ public class InitInterRefiningTest { * @param factorDisruptionA disruption to apply to homothety factor for sensor A * @param rollDisruptionB disruption to apply to roll angle for sensor B (deg) * @param pitchDisruptionB disruption to apply to pitch angle for sensor B (deg) - * @throws RuggedException */ public void initRefiningTest(double rollDisruptionA, double pitchDisruptionA, double factorDisruptionA, - double rollDisruptionB, double pitchDisruptionB) throws RuggedException { + double rollDisruptionB, double pitchDisruptionB) { try { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); @@ -251,9 +248,8 @@ public class InitInterRefiningTest { * @param realPixelA real pixel from sensor A * @param realPixelB real pixel from sensor B * @return the distances of two real pixels computed between LOS and to the ground - * @throws RuggedException */ - public double[] computeDistancesBetweenLOS(final SensorPixel realPixelA, final SensorPixel realPixelB) throws RuggedException { + public double[] computeDistancesBetweenLOS(final SensorPixel realPixelA, final SensorPixel realPixelB) { final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody(); @@ -272,16 +268,10 @@ public class InitInterRefiningTest { * @param realPixelA real pixel from sensor A * @param realPixelB real pixel from sensor B * @return the distances of two real pixels computed between LOS and to the ground - * @throws RuggedException - * @throws SecurityException - * @throws NoSuchMethodException - * @throws InvocationTargetException - * @throws IllegalArgumentException - * @throws IllegalAccessException */ public DerivativeStructure[] computeDistancesBetweenLOSDerivatives(final SensorPixel realPixelA, final SensorPixel realPixelB, double losDistance, double earthDistance) - throws RuggedException, NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { + throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody(); @@ -327,9 +317,8 @@ public class InitInterRefiningTest { * @param pixelSampling pixel sampling * @param earthConstraintWeight the earth constrint weight * @param earthConstraintPostponed flag to tell if the earth constraint weight is set at construction (false) or after (true) - For JUnit coverage purpose - * @throws RuggedException */ - public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) throws RuggedException { + public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) { // Outliers control final double outlierValue = 1.e+2; @@ -437,9 +426,8 @@ public class InitInterRefiningTest { * @param pixelSampling pixel sampling * @param earthConstraintWeight the earth constrint weight * @param earthConstraintPostponed flag to tell if the earth constraint weight is set at construction (false) or after (true) - For JUnit coverage purpose - * @throws RuggedException */ - public Observables generateSimpleInterMapping(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) throws RuggedException { + public Observables generateSimpleInterMapping(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) { // Outliers control final double outlierValue = 1.e+2; diff --git a/src/test/java/org/orekit/rugged/adjustment/util/PleiadesOrbitModel.java b/src/test/java/org/orekit/rugged/adjustment/util/PleiadesOrbitModel.java index bd7ef95ece8207c352b86271f0ca17c713a43020..5f76ebb808a0f108adb6a8eea66650655959c8e3 100644 --- a/src/test/java/org/orekit/rugged/adjustment/util/PleiadesOrbitModel.java +++ b/src/test/java/org/orekit/rugged/adjustment/util/PleiadesOrbitModel.java @@ -14,7 +14,6 @@ import org.orekit.attitudes.NadirPointing; import org.orekit.attitudes.TabulatedLofOffset; import org.orekit.attitudes.YawCompensation; import org.orekit.bodies.BodyShape; -import org.orekit.errors.OrekitException; import org.orekit.frames.Frame; import org.orekit.frames.FramesFactory; import org.orekit.frames.LOFType; @@ -57,7 +56,7 @@ public class PleiadesOrbitModel { /** Create a circular orbit. */ - 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: @@ -109,8 +108,7 @@ public class PleiadesOrbitModel { /** 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); @@ -133,8 +131,7 @@ public class PleiadesOrbitModel { /** 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; @@ -161,8 +158,7 @@ public class PleiadesOrbitModel { */ 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); @@ -185,8 +181,7 @@ public class PleiadesOrbitModel { */ 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/test/java/org/orekit/rugged/adjustment/util/PleiadesViewingModel.java b/src/test/java/org/orekit/rugged/adjustment/util/PleiadesViewingModel.java index 244258a3ba9d3e2ad322f255080c84e5e807b90f..ab7561bbae3607b0ea22e914270572a1cf90c3c7 100644 --- a/src/test/java/org/orekit/rugged/adjustment/util/PleiadesViewingModel.java +++ b/src/test/java/org/orekit/rugged/adjustment/util/PleiadesViewingModel.java @@ -7,7 +7,6 @@ import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.RotationConvention; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.linesensor.LineDatation; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.LinearLineDatation; @@ -15,8 +14,6 @@ import org.orekit.rugged.los.FixedRotation; import org.orekit.rugged.los.FixedZHomothety; import org.orekit.rugged.los.LOSBuilder; import org.orekit.rugged.los.TimeDependentLOS; - -import org.orekit.errors.OrekitException; import org.orekit.time.AbsoluteDate; import org.orekit.time.TimeScale; import org.orekit.time.TimeScalesFactory; @@ -41,8 +38,7 @@ public class PleiadesViewingModel { * @param incidenceAngle incidence angle * @param referenceDate reference date */ - 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.referenceDate = referenceDate; @@ -83,7 +79,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(); @@ -93,13 +89,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); } @@ -124,7 +120,7 @@ public class PleiadesViewingModel { /** 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 diff --git a/src/test/java/org/orekit/rugged/adjustment/util/RefiningParametersDriver.java b/src/test/java/org/orekit/rugged/adjustment/util/RefiningParametersDriver.java index dae8fb87e9c5cb323aff626bccfadc0a72a56678..d4d89bb574c72ee0d5e5d4668c3d7cde973b8f0d 100644 --- a/src/test/java/org/orekit/rugged/adjustment/util/RefiningParametersDriver.java +++ b/src/test/java/org/orekit/rugged/adjustment/util/RefiningParametersDriver.java @@ -1,8 +1,6 @@ package org.orekit.rugged.adjustment.util; -import org.orekit.errors.OrekitException; import org.orekit.rugged.api.Rugged; -import org.orekit.rugged.errors.RuggedException; import org.orekit.utils.ParameterDriver; @@ -21,8 +19,7 @@ public class RefiningParametersDriver { * @param sensorName line sensor name * @param rollValue rotation on roll value */ - public static void applyDisruptionsRoll(final Rugged rugged, final String sensorName, final double rollValue) - throws OrekitException, RuggedException { + public static void applyDisruptionsRoll(final Rugged rugged, final String sensorName, final double rollValue) { rugged. getLineSensor(sensorName). @@ -36,8 +33,7 @@ public class RefiningParametersDriver { * @param sensorName line sensor name * @param pitchValue rotation on pitch value */ - public static void applyDisruptionsPitch(final Rugged rugged, final String sensorName, final double pitchValue) - throws OrekitException, RuggedException { + public static void applyDisruptionsPitch(final Rugged rugged, final String sensorName, final double pitchValue) { rugged. getLineSensor(sensorName). @@ -51,8 +47,7 @@ public class RefiningParametersDriver { * @param sensorName line sensor name * @param factorValue scale factor */ - public static void applyDisruptionsFactor(final Rugged rugged, final String sensorName, final double factorValue) - throws OrekitException, RuggedException { + public static void applyDisruptionsFactor(final Rugged rugged, final String sensorName, final double factorValue) { rugged. getLineSensor(sensorName). @@ -64,9 +59,8 @@ public class RefiningParametersDriver { /** Select roll angle to adjust * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void setSelectedRoll(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void setSelectedRoll(final Rugged rugged, final String sensorName) { ParameterDriver rollDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). @@ -77,9 +71,8 @@ public class RefiningParametersDriver { /** Select pitch angle to adjust * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void setSelectedPitch(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void setSelectedPitch(final Rugged rugged, final String sensorName) { ParameterDriver pitchDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). @@ -90,9 +83,8 @@ public class RefiningParametersDriver { /** Select scale factor to adjust * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void setSelectedFactor(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void setSelectedFactor(final Rugged rugged, final String sensorName) { ParameterDriver factorDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). @@ -103,9 +95,8 @@ public class RefiningParametersDriver { /** Unselect roll angle to adjust (for test coverage purpose) * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void unselectRoll(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void unselectRoll(final Rugged rugged, final String sensorName) { ParameterDriver rollDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). @@ -116,9 +107,8 @@ public class RefiningParametersDriver { /** Unselect pitch angle to adjust (for test coverage purpose) * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void unselectPitch(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void unselectPitch(final Rugged rugged, final String sensorName) { ParameterDriver pitchDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). @@ -129,9 +119,8 @@ public class RefiningParametersDriver { /** Unselect factor angle to adjust (for test coverage purpose) * @param rugged Rugged instance * @param sensorName line sensor name - * @throws OrekitException, RuggedException */ - public static void unselectFactor(final Rugged rugged, final String sensorName) throws OrekitException, RuggedException { + public static void unselectFactor(final Rugged rugged, final String sensorName) { ParameterDriver factorDriver = rugged.getLineSensor(sensorName).getParametersDrivers(). diff --git a/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java b/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java index 0a222ec0b68ad13f85b72114d7984fa9e670836c..3f4c81303d0391f24063f1745d0c92d75c70601a 100644 --- a/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java +++ b/src/test/java/org/orekit/rugged/api/RuggedBuilderTest.java @@ -17,12 +17,6 @@ package org.orekit.rugged.api; -import org.hipparchus.geometry.euclidean.threed.Rotation; -import org.hipparchus.geometry.euclidean.threed.RotationConvention; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; -import org.hipparchus.util.FastMath; - import java.io.ByteArrayInputStream; import java.io.ByteArrayOutputStream; import java.io.EOFException; @@ -36,6 +30,11 @@ import java.util.ArrayList; import java.util.Arrays; import java.util.List; +import org.hipparchus.geometry.euclidean.threed.Rotation; +import org.hipparchus.geometry.euclidean.threed.RotationConvention; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; +import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Rule; import org.junit.Test; @@ -49,7 +48,6 @@ import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.forces.gravity.HolmesFeatherstoneAttractionModel; import org.orekit.forces.gravity.ThirdBodyAttraction; import org.orekit.forces.gravity.potential.GravityFieldFactory; @@ -98,7 +96,7 @@ public class RuggedBuilderTest { @Test public void testSetContextWithEphemerides() - throws RuggedException, OrekitException, URISyntaxException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { + throws URISyntaxException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -314,7 +312,7 @@ public class RuggedBuilderTest { @Test public void testSetContextWithPropagator() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -359,7 +357,7 @@ public class RuggedBuilderTest { @Test public void testOutOfTimeRange() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -461,7 +459,7 @@ public class RuggedBuilderTest { @Test public void testInterpolatorDump() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -530,7 +528,7 @@ public class RuggedBuilderTest { @Test public void testInterpolatorCannotDump() - throws RuggedException, OrekitException, URISyntaxException, IOException { + throws URISyntaxException, IOException { int dimension = 200; @@ -580,7 +578,7 @@ public class RuggedBuilderTest { @Test public void testInterpolatorDumpWrongFrame() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -641,7 +639,7 @@ public class RuggedBuilderTest { @Test public void testInterpolatorNotADump() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -713,8 +711,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 +731,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 +765,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 +820,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); @@ -848,8 +839,8 @@ public class RuggedBuilderTest { 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); diff --git a/src/test/java/org/orekit/rugged/api/RuggedTest.java b/src/test/java/org/orekit/rugged/api/RuggedTest.java index 60eb44093f5ac3892358d6313223479cbb575024..5bd77c9aaa36e0f3c08a6e94256f67c4b9ddbfa6 100644 --- a/src/test/java/org/orekit/rugged/api/RuggedTest.java +++ b/src/test/java/org/orekit/rugged/api/RuggedTest.java @@ -54,7 +54,6 @@ import org.orekit.bodies.GeodeticPoint; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; import org.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; import org.orekit.forces.gravity.potential.NormalizedSphericalHarmonicsProvider; import org.orekit.frames.Frame; import org.orekit.frames.FramesFactory; @@ -65,7 +64,6 @@ import org.orekit.rugged.adjustment.GroundOptimizationProblemBuilder; import org.orekit.rugged.adjustment.measurements.Observables; import org.orekit.rugged.adjustment.util.InitInterRefiningTest; import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedExceptionWrapper; import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.linesensor.LineDatation; import org.orekit.rugged.linesensor.LineSensor; @@ -102,7 +100,7 @@ public class RuggedTest { @Ignore @Test public void testMayonVolcanoTiming() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { long t0 = System.currentTimeMillis(); int dimension = 2000; @@ -193,7 +191,7 @@ public class RuggedTest { @Test public void testLightTimeCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 400; @@ -271,7 +269,7 @@ public class RuggedTest { @Test public void testAberrationOfLightCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 400; @@ -327,7 +325,7 @@ public class RuggedTest { } @Test - public void testAtmosphericRefractionCorrection() throws RuggedException, OrekitException, URISyntaxException { + public void testAtmosphericRefractionCorrection() throws URISyntaxException { String sensorName = "line"; int dimension = 4000; @@ -389,7 +387,7 @@ public class RuggedTest { } // end loop on pixel i } - private RuggedBuilder initRuggedForAtmosphericTests(final int dimension, final String sensorName) throws URISyntaxException, RuggedException { + private RuggedBuilder initRuggedForAtmosphericTests(final int dimension, final String sensorName) throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -439,7 +437,7 @@ public class RuggedTest { @Test public void testFlatBodyCorrection() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -501,7 +499,7 @@ public class RuggedTest { @Test public void testLocationSinglePoint() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -559,7 +557,7 @@ public class RuggedTest { @Test public void testLocationsinglePointNoCorrections() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -620,7 +618,7 @@ public class RuggedTest { @Test public void testBasicScan() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -683,7 +681,7 @@ public class RuggedTest { @Ignore @Test public void testInverseLocationTiming() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { long t0 = System.currentTimeMillis(); int dimension = 2000; @@ -793,7 +791,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); @@ -802,7 +800,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); @@ -811,14 +809,14 @@ public class RuggedTest { @Test public void testLineDatation() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { checkLineDatation(2000, 7.0e-7); checkLineDatation(10000, 8.0e-7); } @Test - public void testInverseLocNearLineEnd() throws OrekitException, RuggedException, URISyntaxException { + public void testInverseLocNearLineEnd() throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -920,7 +918,7 @@ public class RuggedTest { } @Test - public void testInverseLoc() throws OrekitException, RuggedException, URISyntaxException { + public void testInverseLoc() throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); @@ -1021,7 +1019,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))); @@ -1077,7 +1075,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))); @@ -1171,28 +1169,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); } @@ -1205,8 +1203,6 @@ public class RuggedTest { * @param pixelTolerance * @param lineDerivativeRelativeTolerance * @param pixelDerivativeRelativeTolerance - * @throws RuggedException - * @throws OrekitException */ private void doTestInverseLocationDerivatives(int dimension, boolean lightTimeCorrection, @@ -1215,7 +1211,7 @@ public class RuggedTest { double pixelTolerance, double lineDerivativeRelativeTolerance, double pixelDerivativeRelativeTolerance) - throws RuggedException, OrekitException { + { try { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); @@ -1312,60 +1308,36 @@ public class RuggedTest { UnivariateDifferentiableFunction lineVSroll = differentiator.differentiate((double roll) -> { - try { - rollDriver.setValue(roll); - pitchDriver.setValue(0); - return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber(); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } catch (RuggedException e) { - throw new RuggedExceptionWrapper(e); - } + rollDriver.setValue(roll); + pitchDriver.setValue(0); + return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber(); }); double dLdR = lineVSroll.value(factory.variable(0, 0.0)).getPartialDerivative(1); Assert.assertEquals(dLdR, result[0].getPartialDerivative(1, 0), dLdR * lineDerivativeRelativeTolerance); UnivariateDifferentiableFunction lineVSpitch = differentiator.differentiate((double pitch) -> { - try { - rollDriver.setValue(0); - pitchDriver.setValue(pitch); - return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber(); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } catch (RuggedException e) { - throw new RuggedExceptionWrapper(e); - } + rollDriver.setValue(0); + pitchDriver.setValue(pitch); + return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber(); }); double dLdP = lineVSpitch.value(factory.variable(0, 0.0)).getPartialDerivative(1); Assert.assertEquals(dLdP, result[0].getPartialDerivative(0, 1), dLdP * lineDerivativeRelativeTolerance); UnivariateDifferentiableFunction pixelVSroll = differentiator.differentiate((double roll) -> { - try { - rollDriver.setValue(roll); - pitchDriver.setValue(0); - return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber(); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } catch (RuggedException e) { - throw new RuggedExceptionWrapper(e); - } + rollDriver.setValue(roll); + pitchDriver.setValue(0); + return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber(); }); double dXdR = pixelVSroll.value(factory.variable(0, 0.0)).getPartialDerivative(1); Assert.assertEquals(dXdR, result[1].getPartialDerivative(1, 0), dXdR * pixelDerivativeRelativeTolerance); UnivariateDifferentiableFunction pixelVSpitch = differentiator.differentiate((double pitch) -> { - try { - rollDriver.setValue(0); - pitchDriver.setValue(pitch); - return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber(); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } catch (RuggedException e) { - throw new RuggedExceptionWrapper(e); - } + rollDriver.setValue(0); + pitchDriver.setValue(pitch); + return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber(); }); double dXdP = pixelVSpitch.value(factory.variable(0, 0.0)).getPartialDerivative(1); Assert.assertEquals(dXdP, result[1].getPartialDerivative(0, 1), dXdP * pixelDerivativeRelativeTolerance); @@ -1373,7 +1345,7 @@ public class RuggedTest { } catch (InvocationTargetException | NoSuchMethodException | SecurityException | IllegalAccessException | IllegalArgumentException | URISyntaxException | - OrekitExceptionWrapper | RuggedExceptionWrapper e) { + OrekitException | RuggedException e) { Assert.fail(e.getLocalizedMessage()); } } @@ -1381,7 +1353,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))); @@ -1460,7 +1432,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))); @@ -1495,7 +1467,7 @@ public class RuggedTest { } @Test - public void testDistanceBetweenLOS() throws RuggedException { + public void testDistanceBetweenLOS() { InitInterRefiningTest refiningTest = new InitInterRefiningTest(); refiningTest.initRefiningTest(); @@ -1513,7 +1485,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(); @@ -1553,7 +1525,7 @@ public class RuggedTest { @Before - public void setUp() throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { TestUtils.clearFactories(); } } diff --git a/src/test/java/org/orekit/rugged/errors/DumpManagerTest.java b/src/test/java/org/orekit/rugged/errors/DumpManagerTest.java index d2c4dd1b021f8d05480f86b36dc496da62d6f3fd..7b6f3f7036bd5c18f2495e099faadcf50384052d 100644 --- a/src/test/java/org/orekit/rugged/errors/DumpManagerTest.java +++ b/src/test/java/org/orekit/rugged/errors/DumpManagerTest.java @@ -35,7 +35,6 @@ import org.orekit.bodies.BodyShape; import org.orekit.bodies.GeodeticPoint; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.orbits.Orbit; import org.orekit.rugged.TestUtils; import org.orekit.rugged.api.AlgorithmId; @@ -63,7 +62,7 @@ public class DumpManagerTest { public TemporaryFolder tempFolder = new TemporaryFolder(); @Test - public void testDump() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testDump() throws URISyntaxException, IOException { File dump = tempFolder.newFile(); DumpManager.activate(dump); @@ -146,7 +145,7 @@ public class DumpManagerTest { } public void variousRuggedCalls() - throws RuggedException, OrekitException, URISyntaxException { + throws URISyntaxException { int dimension = 200; @@ -209,7 +208,7 @@ public class DumpManagerTest { } @Test - public void testAlreadyActive() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testAlreadyActive() throws URISyntaxException, IOException { DumpManager.activate(tempFolder.newFile()); try { @@ -223,7 +222,7 @@ public class DumpManagerTest { } @Test - public void testNotActive() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testNotActive() throws URISyntaxException, IOException { try { DumpManager.deactivate(); Assert.fail("an exception should have been thrown"); @@ -233,7 +232,7 @@ public class DumpManagerTest { } @Test - public void testWriteError() throws URISyntaxException, IOException, OrekitException, RuggedException { + public void testWriteError() throws URISyntaxException, IOException { try { File dump = tempFolder.newFile(); dump.setReadOnly(); diff --git a/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java b/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java index dae89afafdda5056c77c504addee4ce205c9dfa2..5dce6d2aea7d4dd2dc694819ba5a6847df8e6a07 100644 --- a/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java +++ b/src/test/java/org/orekit/rugged/errors/DumpReplayerTest.java @@ -36,7 +36,6 @@ import org.junit.rules.TemporaryFolder; import org.orekit.bodies.GeodeticPoint; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.rugged.api.Rugged; import org.orekit.rugged.linesensor.SensorPixel; @@ -46,7 +45,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 +68,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 +91,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 +114,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 +145,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 +167,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 +189,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 +211,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 358458269b0acf2cb6bd276bd516becfc79b464a..f9e6998e4a589cc15d8ce8d14631bd4716eed6b9 100644 --- a/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java +++ b/src/test/java/org/orekit/rugged/intersection/AbstractAlgorithmTest.java @@ -17,13 +17,13 @@ package org.orekit.rugged.intersection; +import java.io.File; +import java.net.URISyntaxException; + import org.hipparchus.geometry.euclidean.threed.Line; import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; -import java.io.File; -import java.net.URISyntaxException; - import org.junit.After; import org.junit.Assert; import org.junit.Before; @@ -32,13 +32,10 @@ import org.orekit.attitudes.Attitude; import org.orekit.bodies.GeodeticPoint; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.frames.FramesFactory; import org.orekit.frames.Transform; import org.orekit.orbits.CartesianOrbit; import org.orekit.propagation.SpacecraftState; -import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.intersection.IntersectionAlgorithm; import org.orekit.rugged.intersection.duvenhage.MinMaxTreeTile; import org.orekit.rugged.intersection.duvenhage.MinMaxTreeTileFactory; import org.orekit.rugged.raster.CliffsElevationUpdater; @@ -56,8 +53,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 +90,7 @@ public abstract class AbstractAlgorithmTest { } @Test - public void testMayonVolcanoWithinPixel() - throws RuggedException, OrekitException { + public void testMayonVolcanoWithinPixel() { setUpMayonVolcanoContext(); @@ -121,7 +116,7 @@ public abstract class AbstractAlgorithmTest { @Test public void testCliffsOfMoher() - throws RuggedException, OrekitException { + { setUpCliffsOfMoherContext(); @@ -154,8 +149,7 @@ public abstract class AbstractAlgorithmTest { } - protected void checkIntersection(Vector3D position, Vector3D los, GeodeticPoint intersection) - throws RuggedException { + protected void checkIntersection(Vector3D position, Vector3D los, GeodeticPoint intersection) { // check the point is on the line Line line = new Line(position, new Vector3D(1, position, 1e6, los), 1.0e-12); @@ -170,7 +164,7 @@ public abstract class AbstractAlgorithmTest { } protected void setUpMayonVolcanoContext() - throws RuggedException, OrekitException { + { // Mayon Volcano location according to Wikipedia: 13°15′24″N 123°41′6″E GeodeticPoint summit = @@ -218,7 +212,7 @@ public abstract class AbstractAlgorithmTest { } protected void setUpCliffsOfMoherContext() - throws RuggedException, OrekitException { + { // cliffs of Moher location according to Wikipedia: 52°56′10″N 9°28′15″ W GeodeticPoint north = new GeodeticPoint(FastMath.toRadians(52.9984), @@ -272,8 +266,8 @@ public abstract class AbstractAlgorithmTest { } @Before - public void setUp() - throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { + String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); earth = new ExtendedEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, diff --git a/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java b/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java index f810f6be94f05c44f9b659dfe49ac201d82e9fb0..9b8d6a4ab1e0f7af010d10beceb58b7bd78f1663 100644 --- a/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java +++ b/src/test/java/org/orekit/rugged/intersection/ConstantElevationAlgorithmTest.java @@ -1,4 +1,4 @@ -/* Copyright 2013-2017 CS Systèmes d'Information +/* Copyright 2013-2018 CS Systèmes d'Information * Licensed to CS Systèmes d'Information (CS) under one or more * contributor license agreements. See the NOTICE file distributed with * this work for additional information regarding copyright ownership. @@ -17,12 +17,12 @@ package org.orekit.rugged.intersection; -import org.hipparchus.geometry.euclidean.threed.Rotation; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.util.FastMath; import java.io.File; import java.net.URISyntaxException; +import org.hipparchus.geometry.euclidean.threed.Rotation; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.util.FastMath; import org.junit.After; import org.junit.Assert; import org.junit.Before; @@ -30,11 +30,9 @@ import org.junit.Test; import org.orekit.attitudes.Attitude; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.frames.FramesFactory; import org.orekit.orbits.CartesianOrbit; import org.orekit.propagation.SpacecraftState; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.intersection.duvenhage.DuvenhageAlgorithm; import org.orekit.rugged.raster.CheckedPatternElevationUpdater; import org.orekit.rugged.raster.TileUpdater; @@ -49,7 +47,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 +72,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); @@ -100,8 +98,7 @@ public class ConstantElevationAlgorithmTest { } @Before - public void setUp() - throws OrekitException, URISyntaxException { + public void setUp() throws URISyntaxException { String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath(); DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path))); earth = new ExtendedEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS, 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 cf512a6c3468fefbf77ee8a86a9feca9a7bb37bb..0abf6e556adf7b675f06a2dec3d7ac0a35aff7f5 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,12 +81,12 @@ 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() { - 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); // this geometry is incorrect: // the specified latitude/longitude belong to rows/columns [1, n-1] @@ -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 77cf236a8bf6c5db6b40e8b9a1675303fb9bad3c..1c3c442cd0f8dcab94aab3b8549d0bdfe6299d77 100644 --- a/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java +++ b/src/test/java/org/orekit/rugged/intersection/duvenhage/MinMaxTreeTileTest.java @@ -16,20 +16,19 @@ */ package org.orekit.rugged.intersection.duvenhage; +import java.lang.reflect.Field; + import org.hipparchus.random.RandomGenerator; import org.hipparchus.random.Well1024a; import org.hipparchus.util.FastMath; -import java.lang.reflect.Field; - import org.junit.Assert; import org.junit.Test; -import org.orekit.rugged.errors.RuggedException; 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 +67,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 +95,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 +132,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 +166,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 +181,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 +235,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 +334,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 946e1f0d9c027303989f128c4bcb885547488765..01fbbfb38f2264e26d4cf0f9899fb11140d6384f 100644 --- a/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/FixedRotationTest.java @@ -37,9 +37,6 @@ import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Before; import org.junit.Test; -import org.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.los.FixedRotation; import org.orekit.rugged.los.LOSBuilder; import org.orekit.rugged.los.TimeDependentLOS; @@ -52,7 +49,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) { @@ -74,7 +71,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) { @@ -139,7 +136,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) { @@ -199,20 +196,16 @@ public class FixedRotationTest { int[] orders = new int[selected.size()]; orders[index] = 1; UnivariateDifferentiableMatrixFunction f = - differentiator.differentiate((UnivariateMatrixFunction) x -> { - try { - double oldX = driver.getValue(); - double[][] matrix = new double[raw.size()][]; - driver.setValue(x); - for (int i = 0 ; i < raw.size(); ++i) { - matrix[i] = tdl.getLOS(i, AbsoluteDate.J2000_EPOCH).toArray(); - } - driver.setValue(oldX); - return matrix; - } catch (OrekitException oe) { - throw new OrekitExceptionWrapper(oe); - } - }); + differentiator.differentiate((UnivariateMatrixFunction) x -> { + double oldX = driver.getValue(); + double[][] matrix = new double[raw.size()][]; + driver.setValue(x); + for (int i = 0 ; i < raw.size(); ++i) { + matrix[i] = tdl.getLOS(i, AbsoluteDate.J2000_EPOCH).toArray(); + } + driver.setValue(oldX); + return matrix; + }); DerivativeStructure[][] mDS = f.value(factory11.variable(0, driver.getValue())); for (int i = 0; i < raw.size(); ++i) { Vector3D los = tdl.getLOS(i, AbsoluteDate.J2000_EPOCH); @@ -232,7 +225,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 2734af05eefd0d8ec6036be4de04915112746dd2..9e5102174e06c5c6bf36d3cd73934f74eba30cc4 100644 --- a/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/PolynomialRotationTest.java @@ -38,9 +38,6 @@ import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Before; import org.junit.Test; -import org.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.los.LOSBuilder; import org.orekit.rugged.los.PolynomialRotation; import org.orekit.rugged.los.TimeDependentLOS; @@ -53,7 +50,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) { @@ -75,7 +72,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) { @@ -146,7 +143,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) { @@ -216,20 +213,16 @@ public class PolynomialRotationTest { int[] orders = new int[selected.size()]; orders[index] = 1; UnivariateDifferentiableMatrixFunction f = - differentiator.differentiate((UnivariateMatrixFunction) x -> { - try { - double oldX = driver.getValue(); - double[][] matrix = new double[raw.size()][]; - driver.setValue(x); - for (int i = 0 ; i < raw.size(); ++i) { - matrix[i] = tdl.getLOS(i, date).toArray(); - } - driver.setValue(oldX); - return matrix; - } catch (OrekitException oe) { - throw new OrekitExceptionWrapper(oe); - } - }); + differentiator.differentiate((UnivariateMatrixFunction) x -> { + double oldX = driver.getValue(); + double[][] matrix = new double[raw.size()][]; + driver.setValue(x); + for (int i = 0 ; i < raw.size(); ++i) { + matrix[i] = tdl.getLOS(i, date).toArray(); + } + driver.setValue(oldX); + return matrix; + }); DerivativeStructure[][] mDS = f.value(factory11.variable(0, driver.getValue())); for (int i = 0; i < raw.size(); ++i) { Vector3D los = tdl.getLOS(i, date); @@ -248,7 +241,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 b045b92f68c5d1adb597a0d5a49d4a7e2a8a728a..a0f61bfc8cd23c90d090097a267f89a4df3e5229 100644 --- a/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java +++ b/src/test/java/org/orekit/rugged/linesensor/SensorMeanPlaneCrossingTest.java @@ -16,11 +16,6 @@ */ package org.orekit.rugged.linesensor; -import org.hipparchus.geometry.euclidean.threed.Line; -import org.hipparchus.geometry.euclidean.threed.Vector3D; -import org.hipparchus.random.RandomGenerator; -import org.hipparchus.random.Well19937a; -import org.hipparchus.util.FastMath; import java.io.File; import java.lang.reflect.InvocationTargetException; import java.lang.reflect.Method; @@ -28,6 +23,11 @@ import java.net.URISyntaxException; import java.util.ArrayList; import java.util.List; +import org.hipparchus.geometry.euclidean.threed.Line; +import org.hipparchus.geometry.euclidean.threed.Vector3D; +import org.hipparchus.random.RandomGenerator; +import org.hipparchus.random.Well19937a; +import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Before; import org.junit.Test; @@ -38,7 +38,6 @@ import org.orekit.bodies.GeodeticPoint; import org.orekit.bodies.OneAxisEllipsoid; import org.orekit.data.DataProvidersManager; import org.orekit.data.DirectoryCrawler; -import org.orekit.errors.OrekitException; import org.orekit.frames.FramesFactory; import org.orekit.frames.Transform; import org.orekit.orbits.CircularOrbit; @@ -49,7 +48,6 @@ import org.orekit.propagation.SpacecraftState; import org.orekit.propagation.analytical.KeplerianPropagator; import org.orekit.propagation.sampling.OrekitFixedStepHandler; import org.orekit.rugged.TestUtils; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.linesensor.SensorMeanPlaneCrossing.CrossingResult; import org.orekit.rugged.los.LOSBuilder; import org.orekit.rugged.utils.SpacecraftToObservedBody; @@ -65,7 +63,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 +92,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 +127,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 +221,7 @@ public class SensorMeanPlaneCrossingTest { @Test public void testSlowFind() - throws RuggedException, OrekitException, NoSuchMethodException, + throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException { @@ -287,8 +285,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 +310,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 +330,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 +348,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 ab813e9996269df3c56a0c57ad002788175b73ac..d4349f5e783e798b7128285e7e61d91b23a0c256 100644 --- a/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/CheckedPatternElevationUpdater.java @@ -17,7 +17,6 @@ package org.orekit.rugged.raster; import org.hipparchus.util.FastMath; -import org.orekit.rugged.errors.RuggedException; public class CheckedPatternElevationUpdater implements TileUpdater { @@ -33,8 +32,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 f9d1befe2b3fb7647e550a8ac8af39b138efaa83..ef23c39fef15587ee2f57cdfdb5c9af815251cf8 100644 --- a/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/CliffsElevationUpdater.java @@ -18,7 +18,6 @@ package org.orekit.rugged.raster; import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; -import org.orekit.rugged.errors.RuggedException; public class CliffsElevationUpdater implements TileUpdater { @@ -40,8 +39,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 45e927b3448a41d8ccffdd1a6fc11e5f4abfb1c3..f84b81c76b4750be4e7878036b450be88f9a5708 100644 --- a/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/RandomLandscapeUpdater.java @@ -22,7 +22,6 @@ import org.hipparchus.random.RandomGenerator; import org.hipparchus.random.Well19937a; import org.hipparchus.util.ArithmeticUtils; import org.hipparchus.util.FastMath; -import org.orekit.rugged.errors.RuggedException; public class RandomLandscapeUpdater implements TileUpdater { @@ -37,11 +36,9 @@ public class RandomLandscapeUpdater implements TileUpdater { * @param seed * @param size size in latitude / size in longitude (rad) * @param n number of latitude / number of longitude - * @throws MathIllegalArgumentException */ public RandomLandscapeUpdater(double baseH, double initialScale, double reductionFactor, - long seed, double size, int n) - throws MathIllegalArgumentException { + long seed, double size, int n) { if (!ArithmeticUtils.isPowerOfTwo(n - 1)) { throw new MathIllegalArgumentException(LocalizedCoreFormats.SIMPLE_MESSAGE, @@ -107,8 +104,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 5d7f96db7ae10cd48cb0593c6071c1ffc274a24d..348a40da4e0d099f4770da0463f6638792e3a93f 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 5dd97dac3b0f8cdd76c305dade8b16796b89d705..63e11e3e6d05c75b174fd920943238418cea8add 100644 --- a/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java +++ b/src/test/java/org/orekit/rugged/raster/TilesCacheTest.java @@ -21,14 +21,11 @@ import org.hipparchus.random.Well19937a; import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Test; -import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.raster.SimpleTile; -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 +40,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 +92,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 +120,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 ef19659426eb3c2ef1779a8815868bcc0ed9523f..b8a694cdd6b2c218ebd0dc308a17b94140bab8e5 100644 --- a/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java +++ b/src/test/java/org/orekit/rugged/raster/VolcanicConeElevationUpdater.java @@ -18,7 +18,6 @@ package org.orekit.rugged.raster; import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; -import org.orekit.rugged.errors.RuggedException; import org.orekit.utils.Constants; public class VolcanicConeElevationUpdater implements TileUpdater { @@ -38,8 +37,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 +57,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 63586b030db54fb5d21e49dfe8edcafc6b374a21..dd49730cbe10108a7d68a28c11a7ce9c70ff6823 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 ab2afbd269c3e04973c47b9c6b2682594380d660..4f5de4087f1c89e6a71cc975c3afc7c5c7d976da 100644 --- a/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java +++ b/src/test/java/org/orekit/rugged/refraction/MultiLayerModelTest.java @@ -16,6 +16,11 @@ */ package org.orekit.rugged.refraction; +import java.lang.reflect.Field; +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; + import org.hipparchus.analysis.UnivariateFunction; import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.RotationConvention; @@ -23,7 +28,6 @@ import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; import org.junit.Assert; import org.junit.Test; -import org.orekit.errors.OrekitException; import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.intersection.AbstractAlgorithmTest; @@ -32,15 +36,10 @@ import org.orekit.rugged.intersection.duvenhage.DuvenhageAlgorithm; import org.orekit.rugged.raster.TileUpdater; import org.orekit.rugged.utils.NormalizedGeodeticPoint; -import java.lang.reflect.Field; -import java.util.ArrayList; -import java.util.Collections; -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 +60,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 +88,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 +136,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 +178,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 +203,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 +222,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 +248,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 bbd254875d46b8f64532cea0722f0054d3fccb90..75100472ec5b65e12125d5c3399d0a4c2e782bd1 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 cabacab8ffd0dc73be00624d947e79c371d4bb7f..3c76cef7c6af737e12de1e1199e8dcba5f9656e1 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 558cb928318598694bfdba596cc780335170dde6..8e75d4de2774007f92ee78ace98c91599c9b5aad 100644 --- a/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java +++ b/src/test/java/org/orekit/rugged/utils/RoughVisibilityEstimatorTest.java @@ -16,13 +16,13 @@ */ package org.orekit.rugged.utils; -import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; -import org.hipparchus.util.FastMath; import java.io.File; import java.net.URISyntaxException; import java.util.ArrayList; import java.util.List; +import org.hipparchus.ode.nonstiff.DormandPrince853Integrator; +import org.hipparchus.util.FastMath; import org.junit.After; import org.junit.Assert; import org.junit.Before; @@ -51,7 +51,6 @@ import org.orekit.propagation.Propagator; import org.orekit.propagation.SpacecraftState; import org.orekit.propagation.numerical.NumericalPropagator; import org.orekit.propagation.sampling.OrekitFixedStepHandler; -import org.orekit.rugged.errors.RuggedException; import org.orekit.time.AbsoluteDate; import org.orekit.time.TimeScalesFactory; import org.orekit.utils.Constants; @@ -61,8 +60,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 +85,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 +109,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 +143,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 439a71770867ee3d84cee49ee05ab88e2b5d5a3d..e236cabaf7a4197ef243f3b273667892d840996c 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 be4f57b9339ac79c5eac16c17195f218ac78b355..bdb2f23700bc34b26d1bd342813afb2910b1bb63 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 83ae31997bc8710f59c2ce75196c484d3a4c8b63..f1d056589a92a068d18f1c0f053bd73d814c2b76 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 01dd414d94ed993fff76edf3b663e62fb07f8ac1..aadf6d8623bd1a4083631e8c2088301a5b3fdd62 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 c2e91d755112a86e35e70ed91372899bc718444e..e98cea8deaa6c3a1d8825021cd29b92e9dcc3b3d 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 11bb47b6b2039e96b9bd04d9847b0d543442c80b..31d22ecd491c6f9471d9f97f00dd0c9a5a013699 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 b5dc3072c0363b02087467594db5e4eff8f665b6..9fe09bae06923963ff98bc283fb33db8c6509be3 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/Refining.java @@ -22,15 +22,13 @@ import java.util.Collections; import java.util.List; import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum; -import org.orekit.errors.OrekitException; -import org.orekit.errors.OrekitExceptionWrapper; import org.orekit.rugged.adjustment.AdjustmentContext; -import org.orekit.rugged.api.Rugged; -import org.orekit.rugged.errors.RuggedException; -import org.orekit.rugged.errors.RuggedMessages; import org.orekit.rugged.adjustment.measurements.Observables; import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; +import org.orekit.rugged.api.Rugged; +import org.orekit.rugged.errors.RuggedException; +import org.orekit.rugged.errors.RuggedMessages; import fr.cs.examples.refiningPleiades.generators.GroundMeasurementGenerator; import fr.cs.examples.refiningPleiades.generators.InterMeasurementGenerator; @@ -53,7 +51,7 @@ public class Refining { /** * Constructor */ - public Refining() throws RuggedException { + public Refining() { } /** Apply disruptions on acquisition for roll, pitch and scale factor @@ -62,11 +60,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). @@ -94,11 +90,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); @@ -122,12 +117,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; @@ -158,11 +151,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); @@ -188,12 +180,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; @@ -221,10 +212,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) { @@ -243,11 +233,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"; @@ -263,22 +252,17 @@ 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). getParametersDrivers(). filter(driver -> driver.getName().equals(sensorName + rollSuffix) - || driver.getName().equals(sensorName + pitchSuffix)). + || driver.getName().equals(sensorName + pitchSuffix)). forEach(driver -> { - try { - driver.setSelected(true); - driver.setValue(0.0); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } + driver.setSelected(true); + driver.setValue(0.0); }); rugged. @@ -286,14 +270,10 @@ public class Refining { getParametersDrivers(). filter(driver -> driver.getName().equals(factorName)). forEach(driver -> { - try { - driver.setSelected(isSelected); - - // default value: no Z scale factor applied - driver.setValue(1.0); - } catch (OrekitException e) { - throw new OrekitExceptionWrapper(e); - } + driver.setSelected(isSelected); + + // default value: no Z scale factor applied + driver.setValue(1.0); }); } @@ -302,10 +282,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); @@ -324,11 +303,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); @@ -358,11 +336,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 06192a0257beea23ebfb13664c8ca14d5f020d93..3d15220710784e5c5736e8818ec4f8866f257da5 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/GroundMeasurementGenerator.java @@ -22,12 +22,11 @@ import org.hipparchus.random.UncorrelatedRandomVectorGenerator; import org.hipparchus.random.Well19937a; import org.hipparchus.util.FastMath; 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.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.time.AbsoluteDate; /** Ground measurements generator (sensor to ground mapping). @@ -60,10 +59,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 +94,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 +116,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 +167,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 e09387147e6e585e8cb569742af95415d9b1bb91..bccf204312418685cc07af919732be79aa642d68 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/generators/InterMeasurementGenerator.java @@ -22,7 +22,6 @@ import org.hipparchus.random.Well19937a; import org.orekit.bodies.GeodeticPoint; 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; @@ -84,11 +83,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 +107,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 +127,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 +168,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 +228,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 +313,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 0f778026873bbfe19866a5e973ac0c04f49baedc..ea0b679d4b05e3431570ff81784b062792665b6d 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 3efbc3e4e2ef785e874e7c3fdea56e99bf1b890b..b8125862d6189086a33991e8541d9b37ccdbe872 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/metrics/LocalisationMetrics.java @@ -23,12 +23,11 @@ import java.util.Set; import org.hipparchus.geometry.euclidean.threed.Vector3D; import org.hipparchus.util.FastMath; import org.orekit.bodies.GeodeticPoint; +import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; +import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; import org.orekit.rugged.api.Rugged; -import org.orekit.rugged.errors.RuggedException; import org.orekit.rugged.linesensor.LineSensor; import org.orekit.rugged.linesensor.SensorPixel; -import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping; -import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping; import org.orekit.rugged.utils.SpacecraftToObservedBody; import org.orekit.time.AbsoluteDate; @@ -67,10 +66,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 +82,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 +103,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 +152,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 6f59d297fd8af24ee62e7cd0e1e504680d1b94ad..ddf1e12c7ab1f5759c61e0774163fe183d6e762f 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/OrbitModel.java @@ -31,7 +31,6 @@ import org.orekit.attitudes.TabulatedLofOffset; import org.orekit.attitudes.YawCompensation; import org.orekit.bodies.BodyShape; import org.orekit.bodies.OneAxisEllipsoid; -import org.orekit.errors.OrekitException; import org.orekit.forces.gravity.potential.GravityFieldFactory; import org.orekit.forces.gravity.potential.NormalizedSphericalHarmonicsProvider; import org.orekit.frames.Frame; @@ -91,8 +90,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 +118,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 +128,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 +137,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 +190,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 +213,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 +240,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 +263,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 b54af4efbf63f95a651806c0a665687029bd7c8d..609fb4dc28ae9461ae0de0eafbf24cd257337960 100644 --- a/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java +++ b/src/tutorials/java/fr/cs/examples/refiningPleiades/models/PleiadesViewingModel.java @@ -16,15 +16,16 @@ */ package fr.cs.examples.refiningPleiades.models; +import java.util.ArrayList; +import java.util.List; + import org.hipparchus.geometry.euclidean.threed.Rotation; import org.hipparchus.geometry.euclidean.threed.RotationConvention; import org.hipparchus.geometry.euclidean.threed.Vector3D; - import org.hipparchus.util.FastMath; -import java.util.ArrayList; -import java.util.List; - - +import org.orekit.rugged.linesensor.LineDatation; +import org.orekit.rugged.linesensor.LineSensor; +import org.orekit.rugged.linesensor.LinearLineDatation; import org.orekit.rugged.los.FixedRotation; import org.orekit.rugged.los.FixedZHomothety; import org.orekit.rugged.los.LOSBuilder; @@ -35,13 +36,6 @@ import org.orekit.time.TimeScalesFactory; import fr.cs.examples.refiningPleiades.Refining; -import org.orekit.rugged.linesensor.LinearLineDatation; -import org.orekit.rugged.linesensor.LineDatation; -import org.orekit.rugged.linesensor.LineSensor; - -import org.orekit.rugged.errors.RuggedException; -import org.orekit.errors.OrekitException; - /** * Pleiades viewing model class definition. * The aim of this class is to simulate PHR sensor. @@ -71,7 +65,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 +74,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 +117,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 +127,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 +158,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