Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • orekit/rugged
  • sdinot/rugged
  • yzokras/rugged
  • youngcle/rugged-mod
4 results
Show changes
Showing
with 1845 additions and 1792 deletions
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -16,57 +16,41 @@
*/
package org.orekit.rugged.api;
import java.util.ArrayList;
import java.util.Collection;
import java.util.HashMap;
import java.util.HashSet;
import java.util.List;
import java.util.Map;
import java.util.Set;
import org.hipparchus.analysis.differentiation.Derivative;
import org.hipparchus.analysis.differentiation.DerivativeStructure;
import org.hipparchus.geometry.euclidean.threed.FieldVector3D;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.linear.Array2DRowRealMatrix;
import org.hipparchus.linear.ArrayRealVector;
import org.hipparchus.linear.RealMatrix;
import org.hipparchus.linear.RealVector;
import org.hipparchus.optim.ConvergenceChecker;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresBuilder;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresProblem;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LevenbergMarquardtOptimizer;
import org.hipparchus.optim.nonlinear.vector.leastsquares.GaussNewtonOptimizer;
import org.hipparchus.optim.nonlinear.vector.leastsquares.MultivariateJacobianFunction;
import org.hipparchus.optim.nonlinear.vector.leastsquares.ParameterValidator;
import org.hipparchus.util.FastMath;
import org.hipparchus.util.Pair;
import org.hipparchus.util.MathArrays;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.errors.OrekitException;
import org.orekit.errors.OrekitExceptionWrapper;
import org.orekit.frames.Transform;
import org.orekit.rugged.errors.DumpManager;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedExceptionWrapper;
import org.orekit.rugged.errors.RuggedInternalError;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.intersection.IntersectionAlgorithm;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.SensorMeanPlaneCrossing;
import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.rugged.linesensor.SensorPixelCrossing;
import org.orekit.rugged.utils.DSGenerator;
import org.orekit.rugged.refraction.AtmosphericRefraction;
import org.orekit.rugged.utils.DerivativeGenerator;
import org.orekit.rugged.utils.ExtendedEllipsoid;
import org.orekit.rugged.utils.NormalizedGeodeticPoint;
import org.orekit.rugged.utils.SpacecraftToObservedBody;
import org.orekit.time.AbsoluteDate;
import org.orekit.utils.Constants;
import org.orekit.utils.PVCoordinates;
import org.orekit.utils.ParameterDriver;
/** Main class of Rugged library API.
* @see RuggedBuilder
* @author Luc Maisonobe
* @author Guylaine Prat
* @author Jonathan Guinet
* @author Lucie LabatAllee
*/
public class Rugged {
......@@ -79,11 +63,16 @@ public class Rugged {
*/
private static final double COARSE_INVERSE_LOCATION_ACCURACY = 0.01;
/** Maximum number of evaluations. */
/** Maximum number of evaluations for crossing algorithms. */
private static final int MAX_EVAL = 50;
/** Margin used in parameters estimation for the inverse location lines range. */
private static final int ESTIMATION_LINE_RANGE_MARGIN = 100;
/** Threshold for pixel convergence in fixed point method
* (for inverse location with atmospheric refraction correction). */
private static final double PIXEL_CV_THRESHOLD = 1.e-4;
/** Threshold for line convergence in fixed point method
* (for inverse location with atmospheric refraction correction). */
private static final double LINE_CV_THRESHOLD = 1.e-4;
/** Reference ellipsoid. */
private final ExtendedEllipsoid ellipsoid;
......@@ -106,6 +95,12 @@ public class Rugged {
/** Flag for aberration of light correction. */
private boolean aberrationOfLightCorrection;
/** Rugged name. */
private final String name;
/** Atmospheric refraction for line of sight correction. */
private AtmosphericRefraction atmosphericRefraction;
/** Build a configured instance.
* <p>
* By default, the instance performs both light time correction (which refers
......@@ -121,12 +116,15 @@ public class Rugged {
* @param aberrationOfLightCorrection if true, the aberration of light
* is corrected for more accurate location
* and spacecraft is compensated for more accurate location
* @param atmosphericRefraction the atmospheric refraction model to be used for more accurate location
* @param scToBody transforms interpolator
* @param sensors sensors
* @param name Rugged name
*/
Rugged(final IntersectionAlgorithm algorithm, final ExtendedEllipsoid ellipsoid,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection,
final SpacecraftToObservedBody scToBody, final Collection<LineSensor> sensors) {
Rugged(final IntersectionAlgorithm algorithm, final ExtendedEllipsoid ellipsoid, final boolean lightTimeCorrection,
final boolean aberrationOfLightCorrection, final AtmosphericRefraction atmosphericRefraction,
final SpacecraftToObservedBody scToBody, final Collection<LineSensor> sensors, final String name) {
// space reference
this.ellipsoid = ellipsoid;
......@@ -137,6 +135,10 @@ public class Rugged {
// intersection algorithm
this.algorithm = algorithm;
// Rugged name
// @since 2.0
this.name = name;
this.sensors = new HashMap<String, LineSensor>();
for (final LineSensor s : sensors) {
this.sensors.put(s.getName(), s);
......@@ -145,7 +147,15 @@ public class Rugged {
this.lightTimeCorrection = lightTimeCorrection;
this.aberrationOfLightCorrection = aberrationOfLightCorrection;
this.atmosphericRefraction = atmosphericRefraction;
}
/** Get the Rugged name.
* @return Rugged name
* @since 2.0
*/
public String getName() {
return name;
}
/** Get the DEM intersection algorithm.
......@@ -155,6 +165,14 @@ public class Rugged {
return algorithm;
}
/** Get the DEM intersection algorithm identifier.
* @return DEM intersection algorithm Id
* @since 2.2
*/
public AlgorithmId getAlgorithmId() {
return algorithm.getAlgorithmId();
}
/** Get flag for light time correction.
* @return true if the light time between ground and spacecraft is
* compensated for more accurate location
......@@ -171,6 +189,14 @@ public class Rugged {
return aberrationOfLightCorrection;
}
/** Get the atmospheric refraction model.
* @return atmospheric refraction model
* @since 2.0
*/
public AtmosphericRefraction getRefractionCorrection() {
return atmosphericRefraction;
}
/** Get the line sensors.
* @return line sensors
*/
......@@ -194,7 +220,7 @@ public class Rugged {
/** Check if a date is in the supported range.
* <p>
* The supporte range is given by the {@code minDate} and
* The support range is given by the {@code minDate} and
* {@code maxDate} construction parameters, with an {@code
* overshootTolerance} margin accepted (i.e. a date slightly
* before {@code minDate} or slightly after {@code maxDate}
......@@ -219,67 +245,49 @@ 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) {
// compute the approximate transform between spacecraft and observed body
final LineSensor sensor = getLineSensor(sensorName);
final AbsoluteDate date = sensor.getDate(lineNumber);
final LineSensor sensor = getLineSensor(sensorName);
final Vector3D sensorPosition = sensor.getPosition();
final AbsoluteDate date = sensor.getDate(lineNumber);
// Compute the transform for the date
// from spacecraft to inertial
final Transform scToInert = scToBody.getScToInertial(date);
// from inertial to body
final Transform inertToBody = scToBody.getInertialToBody(date);
final Transform approximate = new Transform(date, scToInert, inertToBody);
final Vector3D spacecraftVelocity =
scToInert.transformPVCoordinates(PVCoordinates.ZERO).getVelocity();
// Compute spacecraft velocity in inertial frame
final Vector3D spacecraftVelocity = scToInert.transformPVCoordinates(PVCoordinates.ZERO).getVelocity();
// Compute sensor position in inertial frame
// TBN: for simplicity, due to the size of sensor, we consider each pixel to be at sensor position
final Vector3D pInert = scToInert.transformPosition(sensorPosition);
// compute location of each pixel
final Vector3D pInert = scToInert.transformPosition(sensor.getPosition());
// Compute location of each pixel
final GeodeticPoint[] gp = new GeodeticPoint[sensor.getNbPixels()];
for (int i = 0; i < sensor.getNbPixels(); ++i) {
DumpManager.dumpDirectLocation(date, sensor.getPosition(), sensor.getLOS(date, i),
lightTimeCorrection, aberrationOfLightCorrection);
final Vector3D los = sensor.getLOS(date, i);
DumpManager.dumpDirectLocation(date, sensorPosition, los, lightTimeCorrection,
aberrationOfLightCorrection, atmosphericRefraction != null);
final Vector3D obsLInert = scToInert.transformVector(sensor.getLOS(date, i));
// compute the line of sight in inertial frame (without correction)
final Vector3D obsLInert = scToInert.transformVector(los);
final Vector3D lInert;
if (aberrationOfLightCorrection) {
// apply aberration of light correction
// as the spacecraft velocity is small with respect to speed of light,
// we use classical velocity addition and not relativistic velocity addition
// we look for a positive k such that: c * lInert + vsat = k * obsLInert
// with lInert normalized
final double a = obsLInert.getNormSq();
final double b = -Vector3D.dotProduct(obsLInert, spacecraftVelocity);
final double c = spacecraftVelocity.getNormSq() - Constants.SPEED_OF_LIGHT * Constants.SPEED_OF_LIGHT;
final double s = FastMath.sqrt(b * b - a * c);
final double k = (b > 0) ? -c / (s + b) : (s - b) / a;
lInert = new Vector3D( k / Constants.SPEED_OF_LIGHT, obsLInert,
-1.0 / Constants.SPEED_OF_LIGHT, spacecraftVelocity);
// apply aberration of light correction on LOS
lInert = applyAberrationOfLightCorrection(obsLInert, spacecraftVelocity);
} else {
// don't apply aberration of light correction
// don't apply aberration of light correction on LOS
lInert = obsLInert;
}
if (lightTimeCorrection) {
// compute DEM intersection with light time correction
final Vector3D sP = approximate.transformPosition(sensor.getPosition());
final Vector3D sL = approximate.transformVector(sensor.getLOS(date, i));
final Vector3D eP1 = ellipsoid.transform(ellipsoid.pointOnGround(sP, sL, 0.0));
final double deltaT1 = eP1.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted1 = inertToBody.shiftedBy(-deltaT1);
final NormalizedGeodeticPoint gp1 = algorithm.intersection(ellipsoid,
shifted1.transformPosition(pInert),
shifted1.transformVector(lInert));
final Vector3D eP2 = ellipsoid.transform(gp1);
final double deltaT2 = eP2.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted2 = inertToBody.shiftedBy(-deltaT2);
gp[i] = algorithm.refineIntersection(ellipsoid,
shifted2.transformPosition(pInert),
shifted2.transformVector(lInert),
gp1);
// TBN: for simplicity, due to the size of sensor, we consider each pixel to be at sensor position
gp[i] = computeWithLightTimeCorrection(date, sensorPosition, los, scToInert, inertToBody, pInert, lInert);
} else {
// compute DEM intersection without light time correction
......@@ -289,94 +297,90 @@ public class Rugged {
algorithm.intersection(ellipsoid, pBody, lBody));
}
DumpManager.dumpDirectLocationResult(gp[i]);
// compute with atmospheric refraction correction if necessary
if (atmosphericRefraction != null && atmosphericRefraction.mustBeComputed()) {
// apply atmospheric refraction correction
final Vector3D pBody = inertToBody.transformPosition(pInert);
final Vector3D lBody = inertToBody.transformVector(lInert);
gp[i] = atmosphericRefraction.applyCorrection(pBody, lBody, (NormalizedGeodeticPoint) gp[i], algorithm);
}
DumpManager.dumpDirectLocationResult(gp[i]);
}
return gp;
}
/** Direct location of a single line-of-sight.
* @param date date of the location
* @param position pixel position in spacecraft frame
* @param sensorPosition sensor position in spacecraft frame. For simplicity, due to the size of sensor,
* 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, or sensor is unknown
*/
public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D position, final Vector3D los)
throws RuggedException {
public GeodeticPoint directLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los) {
DumpManager.dumpDirectLocation(date, position, los, lightTimeCorrection, aberrationOfLightCorrection);
DumpManager.dumpDirectLocation(date, sensorPosition, los, lightTimeCorrection, aberrationOfLightCorrection,
atmosphericRefraction != null);
// compute the approximate transform between spacecraft and observed body
// Compute the transforms for the date
// from spacecraft to inertial
final Transform scToInert = scToBody.getScToInertial(date);
// from inertial to body
final Transform inertToBody = scToBody.getInertialToBody(date);
final Transform approximate = new Transform(date, scToInert, inertToBody);
final Vector3D spacecraftVelocity =
scToInert.transformPVCoordinates(PVCoordinates.ZERO).getVelocity();
// compute location of specified pixel
final Vector3D pInert = scToInert.transformPosition(position);
// Compute spacecraft velocity in inertial frame
final Vector3D spacecraftVelocity = scToInert.transformPVCoordinates(PVCoordinates.ZERO).getVelocity();
// Compute sensor position in inertial frame
// TBN: for simplicity, due to the size of sensor, we consider each pixel to be at sensor position
final Vector3D pInert = scToInert.transformPosition(sensorPosition);
// Compute the line of sight in inertial frame (without correction)
final Vector3D obsLInert = scToInert.transformVector(los);
final Vector3D lInert;
if (aberrationOfLightCorrection) {
// apply aberration of light correction
// as the spacecraft velocity is small with respect to speed of light,
// we use classical velocity addition and not relativistic velocity addition
// we look for a positive k such that: c * lInert + vsat = k * obsLInert
// with lInert normalized
final double a = obsLInert.getNormSq();
final double b = -Vector3D.dotProduct(obsLInert, spacecraftVelocity);
final double c = spacecraftVelocity.getNormSq() - Constants.SPEED_OF_LIGHT * Constants.SPEED_OF_LIGHT;
final double s = FastMath.sqrt(b * b - a * c);
final double k = (b > 0) ? -c / (s + b) : (s - b) / a;
lInert = new Vector3D( k / Constants.SPEED_OF_LIGHT, obsLInert,
-1.0 / Constants.SPEED_OF_LIGHT, spacecraftVelocity);
// apply aberration of light correction on LOS
lInert = applyAberrationOfLightCorrection(obsLInert, spacecraftVelocity);
} else {
// don't apply aberration of light correction
// don't apply aberration of light correction on LOS
lInert = obsLInert;
}
final NormalizedGeodeticPoint result;
// Compute ground location of specified pixel
final NormalizedGeodeticPoint gp;
if (lightTimeCorrection) {
// compute DEM intersection with light time correction
final Vector3D sP = approximate.transformPosition(position);
final Vector3D sL = approximate.transformVector(los);
final Vector3D eP1 = ellipsoid.transform(ellipsoid.pointOnGround(sP, sL, 0.0));
final double deltaT1 = eP1.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted1 = inertToBody.shiftedBy(-deltaT1);
final NormalizedGeodeticPoint gp1 = algorithm.intersection(ellipsoid,
shifted1.transformPosition(pInert),
shifted1.transformVector(lInert));
final Vector3D eP2 = ellipsoid.transform(gp1);
final double deltaT2 = eP2.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted2 = inertToBody.shiftedBy(-deltaT2);
result = algorithm.refineIntersection(ellipsoid,
shifted2.transformPosition(pInert),
shifted2.transformVector(lInert),
gp1);
// TBN: for simplicity, due to the size of sensor, we consider each pixel to be at sensor position
gp = computeWithLightTimeCorrection(date, sensorPosition, los, scToInert, inertToBody, pInert, lInert);
} else {
// compute DEM intersection without light time correction
final Vector3D pBody = inertToBody.transformPosition(pInert);
final Vector3D lBody = inertToBody.transformVector(lInert);
result = algorithm.refineIntersection(ellipsoid, pBody, lBody,
algorithm.intersection(ellipsoid, pBody, lBody));
gp = algorithm.refineIntersection(ellipsoid, pBody, lBody,
algorithm.intersection(ellipsoid, pBody, lBody));
}
NormalizedGeodeticPoint result = gp;
// compute the ground location with atmospheric correction if asked for
if (atmosphericRefraction != null && atmosphericRefraction.mustBeComputed()) {
// apply atmospheric refraction correction
final Vector3D pBody = inertToBody.transformPosition(pInert);
final Vector3D lBody = inertToBody.transformVector(lInert);
result = atmosphericRefraction.applyCorrection(pBody, lBody, gp, algorithm);
} // end test on atmosphericRefraction != null
DumpManager.dumpDirectLocationResult(result);
return result;
}
/** Find the date at which sensor sees a ground point.
* <p>
* This method is a partial {@link #inverseLocation(String,
* GeodeticPoint, int, int) inverse location} focusing only on date.
* This method is a partial {@link #inverseLocation(String, GeodeticPoint, int, int) inverse location} focusing only on date.
* </p>
* <p>
* The point is given only by its latitude and longitude, the elevation is
......@@ -396,19 +400,18 @@ public class Rugged {
* are only an example and should be adjusted depending on mission needs.
* </p>
* @param sensorName name of the line sensor
* @param latitude ground point latitude
* @param longitude ground point longitude
* @param latitude ground point latitude (rad)
* @param longitude ground point longitude (rad)
* @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);
......@@ -432,18 +435,16 @@ public class Rugged {
* an inverse location is expected to occur after 55750. Of course, these values
* are only an example and should be adjusted depending on mission needs.
* </p>
* @param sensorName name of the line sensor
* @param sensorName name of the line sensor
* @param point point to localize
* @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);
......@@ -457,7 +458,6 @@ public class Rugged {
} else {
return sensor.getDate(crossingResult.getLine());
}
}
/** Inverse location of a ground point.
......@@ -479,21 +479,19 @@ public class Rugged {
* are only an example and should be adjusted depending on mission needs.
* </p>
* @param sensorName name of the line sensor
* @param latitude ground point latitude
* @param longitude ground point longitude
* @param latitude ground point latitude (rad)
* @param longitude ground point longitude (rad)
* @param minLine minimum line number
* @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 GeodeticPoint groundPoint =
new GeodeticPoint(latitude, longitude, algorithm.getElevation(latitude, longitude));
final int minLine, final int maxLine) {
final GeodeticPoint groundPoint = new GeodeticPoint(latitude, longitude, algorithm.getElevation(latitude, longitude));
return inverseLocation(sensorName, groundPoint, minLine, maxLine);
}
......@@ -511,30 +509,109 @@ public class Rugged {
* an inverse location is expected to occur after 55750. Of course, these values
* are only an example and should be adjusted depending on mission needs.
* </p>
* @param sensorName name of the line sensor
* @param point point to localize
* @param minLine minimum line number
* @param maxLine maximum line number
* @param sensorName name of the line sensor
* @param point geodetic point to localize
* @param minLine minimum line number where the search will be performed
* @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);
DumpManager.dumpInverseLocation(sensor, point, ellipsoid, minLine, maxLine, lightTimeCorrection,
aberrationOfLightCorrection, atmosphericRefraction != null);
final SensorMeanPlaneCrossing planeCrossing = getPlaneCrossing(sensorName, minLine, maxLine);
DumpManager.dumpSensorMeanPlane(planeCrossing);
if (atmosphericRefraction == null || !atmosphericRefraction.mustBeComputed()) {
// Compute inverse location WITHOUT atmospheric refraction
return findSensorPixelWithoutAtmosphere(point, sensor, planeCrossing);
} else {
// Compute inverse location WITH atmospheric refraction
return findSensorPixelWithAtmosphere(point, sensor, minLine, maxLine);
}
}
/** Apply aberration of light correction (for direct location).
* @param spacecraftVelocity spacecraft velocity in inertial frame
* @param obsLInert line of sight in inertial frame
* @return line of sight with aberration of light correction
*/
private Vector3D applyAberrationOfLightCorrection(final Vector3D obsLInert, final Vector3D spacecraftVelocity) {
// As the spacecraft velocity is small with respect to speed of light,
// we use classical velocity addition and not relativistic velocity addition
// we look for a positive k such that: c * lInert + vsat = k * obsLInert
// with lInert normalized
final double a = obsLInert.getNormSq();
final double b = -Vector3D.dotProduct(obsLInert, spacecraftVelocity);
final double c = spacecraftVelocity.getNormSq() - Constants.SPEED_OF_LIGHT * Constants.SPEED_OF_LIGHT;
// a > 0 and c < 0
final double s = FastMath.sqrt(b * b - a * c);
// Only the k > 0 are kept as solutions (the solutions: -(s+b)/a and c/(s-b) are useless)
final double k = (b > 0) ? -c / (s + b) : (s - b) / a;
final Vector3D lInert = new Vector3D( k / Constants.SPEED_OF_LIGHT, obsLInert, -1.0 / Constants.SPEED_OF_LIGHT, spacecraftVelocity);
return lInert;
}
/** Compute the DEM intersection with light time correction.
* @param date date of the los
* @param sensorPosition sensor position in spacecraft frame
* @param los los in spacecraft frame
* @param scToInert transform for the date from spacecraft to inertial
* @param inertToBody transform for the date from inertial to body
* @param pInert sensor position in inertial frame
* @param lInert line of sight in inertial frame
* @return geodetic point with light time correction
*/
private NormalizedGeodeticPoint computeWithLightTimeCorrection(final AbsoluteDate date,
final Vector3D sensorPosition, final Vector3D los,
final Transform scToInert, final Transform inertToBody,
final Vector3D pInert, final Vector3D lInert) {
// compute the approximate transform between spacecraft and observed body
final Transform approximate = new Transform(date, scToInert, inertToBody);
final Vector3D sL = approximate.transformVector(los);
final Vector3D sP = approximate.transformPosition(sensorPosition);
final Vector3D eP1 = ellipsoid.transform(ellipsoid.pointOnGround(sP, sL, 0.0));
final double deltaT1 = eP1.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted1 = inertToBody.shiftedBy(-deltaT1);
final NormalizedGeodeticPoint gp1 = algorithm.intersection(ellipsoid,
shifted1.transformPosition(pInert),
shifted1.transformVector(lInert));
final Vector3D eP2 = ellipsoid.transform(gp1);
final double deltaT2 = eP2.distance(sP) / Constants.SPEED_OF_LIGHT;
final Transform shifted2 = inertToBody.shiftedBy(-deltaT2);
return algorithm.refineIntersection(ellipsoid,
shifted2.transformPosition(pInert),
shifted2.transformVector(lInert),
gp1);
}
/**
* Find the sensor pixel WITHOUT atmospheric refraction correction.
* @param point geodetic point to localize
* @param sensor the line sensor
* @param planeCrossing the sensor mean plane crossing
* @return the sensor pixel crossing or null if cannot be found
* @since 2.1
*/
private SensorPixel findSensorPixelWithoutAtmosphere(final GeodeticPoint point,
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);
final Vector3D target = ellipsoid.transform(point);
final SensorMeanPlaneCrossing.CrossingResult crossingResult = planeCrossing.find(target);
if (crossingResult == null) {
// target is out of search interval
......@@ -558,10 +635,8 @@ public class Rugged {
final Vector3D lowLOS = sensor.getLOS(crossingResult.getDate(), lowIndex);
final Vector3D highLOS = sensor.getLOS(crossingResult.getDate(), lowIndex + 1);
final Vector3D localZ = Vector3D.crossProduct(lowLOS, highLOS).normalize();
final double beta = FastMath.acos(Vector3D.dotProduct(crossingResult.getTargetDirection(),
localZ));
final double s = Vector3D.dotProduct(crossingResult.getTargetDirectionDerivative(),
localZ);
final double beta = FastMath.acos(Vector3D.dotProduct(crossingResult.getTargetDirection(), localZ));
final double s = Vector3D.dotProduct(crossingResult.getTargetDirectionDerivative(), localZ);
final double betaDer = -s / FastMath.sqrt(1 - s * s);
final double deltaL = (0.5 * FastMath.PI - beta) / betaDer;
final double fixedLine = crossingResult.getLine() + deltaL;
......@@ -583,292 +658,416 @@ public class Rugged {
final SensorPixel result = new SensorPixel(fixedLine, fixedPixel);
DumpManager.dumpInverseLocationResult(result);
return result;
}
/**
* Find the sensor pixel WITH atmospheric refraction correction.
* @param point geodetic point to localize
* @param sensor the line sensor
* @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
* @since 2.1
*/
private SensorPixel findSensorPixelWithAtmosphere(final GeodeticPoint point,
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
final String sensorName = sensor.getName();
// Compute a correction grid (at sensor level)
// ===========================================
// Need to be computed only once for a given sensor (with the same minLine and maxLine)
if (atmosphericRefraction.getBifPixel() == null || atmosphericRefraction.getBifLine() == null || // lazy evaluation
!atmosphericRefraction.isSameContext(sensorName, minLine, maxLine)) { // Must be recomputed if the context changed
// Definition of a regular grid (at sensor level)
atmosphericRefraction.configureCorrectionGrid(sensor, minLine, maxLine);
// Get the grid nodes
final int nbPixelGrid = atmosphericRefraction.getComputationParameters().getNbPixelGrid();
final int nbLineGrid = atmosphericRefraction.getComputationParameters().getNbLineGrid();
final double[] pixelGrid = atmosphericRefraction.getComputationParameters().getUgrid();
final double[] lineGrid = atmosphericRefraction.getComputationParameters().getVgrid();
// Computation, for the sensor grid, of the direct location WITH atmospheric refraction
// (full computation)
atmosphericRefraction.reactivateComputation();
final GeodeticPoint[][] geodeticGridWithAtmosphere = computeDirectLocOnGridWithAtmosphere(pixelGrid, lineGrid, sensor);
// pixelGrid and lineGrid are the nodes where the direct loc is computed WITH atmosphere
// Computation of the inverse location WITHOUT atmospheric refraction for the grid nodes
atmosphericRefraction.deactivateComputation();
final SensorPixel[][] sensorPixelGridInverseWithout = computeInverseLocOnGridWithoutAtmosphere(geodeticGridWithAtmosphere,
nbPixelGrid, nbLineGrid, sensor, minLine, maxLine);
atmosphericRefraction.reactivateComputation();
// Compute the grid correction functions (for pixel and line)
atmosphericRefraction.computeGridCorrectionFunctions(sensorPixelGridInverseWithout);
}
// Fixed point method
// ==================
// Initialization
// --------------
// Deactivate the dump because no need to keep intermediate computations of inverse loc (can be regenerate)
final Boolean wasSuspended = DumpManager.suspend();
// compute the sensor pixel on the desired ground point WITHOUT atmosphere
atmosphericRefraction.deactivateComputation();
final SensorPixel sp0 = inverseLocation(sensorName, point, minLine, maxLine);
atmosphericRefraction.reactivateComputation();
// Reactivate the dump
DumpManager.resume(wasSuspended);
if (sp0 == null) {
// In order for the dump to end nicely
DumpManager.endNicely();
// Impossible to find the sensor pixel in the given range lines (without atmosphere)
throw new RuggedException(RuggedMessages.SENSOR_PIXEL_NOT_FOUND_IN_RANGE_LINES, minLine, maxLine);
}
// set up the starting point of the fixed point method
final double pixel0 = sp0.getPixelNumber();
final double line0 = sp0.getLineNumber();
// Needed data for the dump
sensor.dumpRate(line0);
// Apply fixed point method until convergence in pixel and line
// ------------------------------------------------------------
// compute the first (pixel, line) value:
// initial sensor pixel value + correction due to atmosphere at this same sensor pixel
double corrPixelPrevious = pixel0 + atmosphericRefraction.getBifPixel().value(pixel0, line0);
double corrLinePrevious = line0 + atmosphericRefraction.getBifLine().value(pixel0, line0);
double deltaCorrPixel = Double.POSITIVE_INFINITY;
double deltaCorrLine = Double.POSITIVE_INFINITY;
while (deltaCorrPixel > PIXEL_CV_THRESHOLD && deltaCorrLine > LINE_CV_THRESHOLD) {
// Compute the current (pixel, line) value =
// initial sensor pixel value + correction due to atmosphere on the previous sensor pixel
final double corrPixelCurrent = pixel0 + atmosphericRefraction.getBifPixel().value(corrPixelPrevious, corrLinePrevious);
final double corrLineCurrent = line0 + atmosphericRefraction.getBifLine().value(corrPixelPrevious, corrLinePrevious);
// Compute the delta in pixel and line to check the convergence
deltaCorrPixel = FastMath.abs(corrPixelCurrent - corrPixelPrevious);
deltaCorrLine = FastMath.abs(corrLineCurrent - corrLinePrevious);
// Store the (pixel, line) for next loop
corrPixelPrevious = corrPixelCurrent;
corrLinePrevious = corrLineCurrent;
}
// The sensor pixel is found !
final SensorPixel sensorPixelWithAtmosphere = new SensorPixel(corrLinePrevious, corrPixelPrevious);
// Dump the found sensorPixel
DumpManager.dumpInverseLocationResult(sensorPixelWithAtmosphere);
return sensorPixelWithAtmosphere;
}
/** Compute the inverse location WITHOUT atmospheric refraction for the geodetic points
* associated to the sensor grid nodes.
* @param groundGridWithAtmosphere ground grid found for sensor grid nodes with atmosphere
* @param nbPixelGrid size of the pixel grid
* @param nbLineGrid size of the line grid
* @param sensor the line sensor
* @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
* @since 2.1
*/
private SensorPixel[][] computeInverseLocOnGridWithoutAtmosphere(final GeodeticPoint[][] groundGridWithAtmosphere,
final int nbPixelGrid, final int nbLineGrid,
final LineSensor sensor, final int minLine, final int maxLine) {
// Deactivate the dump because no need to keep intermediate computations of inverse loc (can be regenerate)
final Boolean wasSuspended = DumpManager.suspend();
final SensorPixel[][] sensorPixelGrid = new SensorPixel[nbPixelGrid][nbLineGrid];
final String sensorName = sensor.getName();
for (int uIndex = 0; uIndex < nbPixelGrid; uIndex++) {
for (int vIndex = 0; vIndex < nbLineGrid; vIndex++) {
// Check if the geodetic point exists
if (groundGridWithAtmosphere[uIndex][vIndex] != null) {
final GeodeticPoint groundPoint = groundGridWithAtmosphere[uIndex][vIndex];
final double currentLat = groundPoint.getLatitude();
final double currentLon = groundPoint.getLongitude();
try {
// Compute the inverse location for the current node
sensorPixelGrid[uIndex][vIndex] = inverseLocation(sensorName, currentLat, currentLon, minLine, maxLine);
} catch (RuggedException re) { // This should never happen
// In order for the dump to end nicely
DumpManager.endNicely();
throw new RuggedInternalError(re);
}
// Check if the pixel is inside the sensor (with a margin) OR if the inverse location was impossible (null result)
if (!pixelIsInside(sensorPixelGrid[uIndex][vIndex], sensor)) {
// In order for the dump to end nicely
DumpManager.endNicely();
if (sensorPixelGrid[uIndex][vIndex] == null) {
// Impossible to find the sensor pixel in the given range lines
throw new RuggedException(RuggedMessages.SENSOR_PIXEL_NOT_FOUND_IN_RANGE_LINES, minLine, maxLine);
} else {
// Impossible to find the sensor pixel
final double invLocationMargin = atmosphericRefraction.getComputationParameters().getInverseLocMargin();
throw new RuggedException(RuggedMessages.SENSOR_PIXEL_NOT_FOUND_IN_PIXELS_LINE, sensorPixelGrid[uIndex][vIndex].getPixelNumber(),
-invLocationMargin, invLocationMargin + sensor.getNbPixels() - 1, invLocationMargin);
}
}
} else { // groundGrid[uIndex][vIndex] == null: impossible to compute inverse loc because ground point not defined
sensorPixelGrid[uIndex][vIndex] = null;
} // groundGrid[uIndex][vIndex] != null
} // end loop vIndex
} // end loop uIndex
// Reactivate the dump
DumpManager.resume(wasSuspended);
// The sensor grid computed WITHOUT atmospheric refraction correction
return sensorPixelGrid;
}
/** Check if pixel is inside the sensor with a margin.
* @param pixel pixel to check (may be null if not found)
* @param sensor the line sensor
* @return true if the pixel is inside the sensor
*/
private boolean pixelIsInside(final SensorPixel pixel, final LineSensor sensor) {
// Get the inverse location margin
final double invLocationMargin = atmosphericRefraction.getComputationParameters().getInverseLocMargin();
return pixel != null && pixel.getPixelNumber() >= -invLocationMargin && pixel.getPixelNumber() < invLocationMargin + sensor.getNbPixels() - 1;
}
/** Computation, for the sensor pixels grid, of the direct location WITH atmospheric refraction.
* (full computation)
* @param pixelGrid the pixel grid
* @param lineGrid the line grid
* @param sensor the line sensor
* @return the ground grid computed with atmosphere
* @since 2.1
*/
private GeodeticPoint[][] computeDirectLocOnGridWithAtmosphere(final double[] pixelGrid, final double[] lineGrid,
final LineSensor sensor) {
// Deactivate the dump because no need to keep intermediate computations of direct loc (can be regenerate)
final Boolean wasSuspended = DumpManager.suspend();
final int nbPixelGrid = pixelGrid.length;
final int nbLineGrid = lineGrid.length;
final GeodeticPoint[][] groundGridWithAtmosphere = new GeodeticPoint[nbPixelGrid][nbLineGrid];
final Vector3D sensorPosition = sensor.getPosition();
for (int uIndex = 0; uIndex < nbPixelGrid; uIndex++) {
final double pixelNumber = pixelGrid[uIndex];
for (int vIndex = 0; vIndex < nbLineGrid; vIndex++) {
final double lineNumber = lineGrid[vIndex];
final AbsoluteDate date = sensor.getDate(lineNumber);
final Vector3D los = sensor.getLOS(date, pixelNumber);
try {
// Compute the direct location for the current node
groundGridWithAtmosphere[uIndex][vIndex] = directLocation(date, sensorPosition, los);
} catch (RuggedException re) { // This should never happen
// In order for the dump to end nicely
DumpManager.endNicely();
throw new RuggedInternalError(re);
}
} // end loop vIndex
} // end loop uIndex
// Reactivate the dump
DumpManager.resume(wasSuspended);
// The ground grid computed WITH atmospheric refraction correction
return groundGridWithAtmosphere;
}
/** Compute distance between two line sensors.
/** Compute distances between two line sensors.
* @param sensorA line sensor A
* @param dateA current date for sensor A
* @param pixelA pixel index for sensor A
* @param scToBodyA spacecraft to body transform for sensor A
* @param sensorB line sensor B
* @param dateB current date for sensor B
* @param pixelB pixel index for sensor B
* @return distance computing
* @exception RuggedException if sensor is unknown
* @return distances computed between LOS and to the ground
* @since 2.0
*/
public double distanceBetweenLOS(final LineSensor sensorA,
final AbsoluteDate dateA, final int pixelA,
final LineSensor sensorB,
final AbsoluteDate dateB, final int pixelB)
throws RuggedException {
//final LineSensor sensorA = getLineSensor(sensorNameA);
//final LineSensor sensorB = getLineSensor(sensorNameB);
// Get sensors's position and LOS
final Vector3D vA = sensorA.getLOS(dateA, pixelA); // V_a : line of sight's vectorA
final Vector3D vB = sensorB.getLOS(dateB, pixelB); // V_b
final Vector3D sA = sensorA.getPosition(); // S_a : sensorA 's position
final Vector3D sB = sensorB.getPosition(); // S_b
final Vector3D vBase= sB.subtract(sA); // S_b - S_a
final double svA = Vector3D.dotProduct(vBase, vA); // SV_a = (S_b - S_a).V_a
final double svB = Vector3D.dotProduct(vBase, vB); // SV_b = (S_b - S_a).V_b
final double vAvB = Vector3D.dotProduct(vA, vB); // V_a.V_b
// Compute lambda_b = (SV_a * V_a.V_b - SV_b) / (1 + (V_a.V_b)²)
final double lambdaB = (svA * vAvB - svB) / (1 + FastMath.pow(vAvB,2));
public double[] distanceBetweenLOS(final LineSensor sensorA, final AbsoluteDate dateA, final double pixelA,
final SpacecraftToObservedBody scToBodyA,
final LineSensor sensorB, final AbsoluteDate dateB, final double pixelB) {
// Compute the approximate transform between spacecraft and observed body
// from Rugged instance A
final Transform scToInertA = scToBodyA.getScToInertial(dateA);
final Transform inertToBodyA = scToBodyA.getInertialToBody(dateA);
final Transform transformScToBodyA = new Transform(dateA, scToInertA, inertToBodyA);
// from (current) Rugged instance B
final Transform scToInertB = scToBody.getScToInertial(dateB);
final Transform inertToBodyB = scToBody.getInertialToBody(dateB);
final Transform transformScToBodyB = new Transform(dateB, scToInertB, inertToBodyB);
// Get sensors LOS into local frame
final Vector3D vALocal = sensorA.getLOS(dateA, pixelA);
final Vector3D vBLocal = sensorB.getLOS(dateB, pixelB);
// Position of sensors into local frame
final Vector3D sALocal = sensorA.getPosition(); // S_a : sensorA 's position
final Vector3D sBLocal = sensorB.getPosition(); // S_b : sensorB 's position
// Get sensors position and LOS into body frame
final Vector3D sA = transformScToBodyA.transformPosition(sALocal); // S_a : sensorA's position
final Vector3D vA = transformScToBodyA.transformVector(vALocal); // V_a : line of sight's vectorA
final Vector3D sB = transformScToBodyB.transformPosition(sBLocal); // S_b : sensorB's position
final Vector3D vB = transformScToBodyB.transformVector(vBLocal); // V_b : line of sight's vectorB
// Compute distance
final Vector3D vBase = sB.subtract(sA); // S_b - S_a
final double svA = Vector3D.dotProduct(vBase, vA); // SV_a = (S_b - S_a).V_a
final double svB = Vector3D.dotProduct(vBase, vB); // SV_b = (S_b - S_a).V_b
final double vAvB = Vector3D.dotProduct(vA, vB); // V_a.V_b
// Compute lambda_b = (SV_a * V_a.V_b - SV_b) / (1 - (V_a.V_b)²)
final double lambdaB = (svA * vAvB - svB) / (1 - vAvB * vAvB);
// Compute lambda_a = SV_a + lambdaB * V_a.V_b
final double lambdaA = svA + lambdaB * vAvB;
final Vector3D mA = sA.add(vA.scalarMultiply(lambdaA)); // M_a = S_a + lambda_a * V_a
final Vector3D mB = sB.add(vB.scalarMultiply(lambdaB)); // M_b = S_b + lambda_b * V_b
final Vector3D vDistance = mB.subtract(mA); // M_b - M_a
// Get square of the euclidean norm
final double d = vDistance.getNormSq();
return d;
final double lambdaA = svA + lambdaB * vAvB;
// Compute vector M_a = S_a + lambda_a * V_a
final Vector3D mA = sA.add(vA.scalarMultiply(lambdaA));
// Compute vector M_b = S_b + lambda_b * V_b
final Vector3D mB = sB.add(vB.scalarMultiply(lambdaB));
// Compute vector M_a -> M_B for which distance between LOS is minimum
final Vector3D vDistanceMin = mB.subtract(mA); // M_b - M_a
// Compute vector from mid point of vector M_a -> M_B to the ground (corresponds to minimum elevation)
final Vector3D midPoint = (mB.add(mA)).scalarMultiply(0.5);
// Get the euclidean norms to compute the minimum distances: between LOS and to the ground
final double[] distances = {vDistanceMin.getNorm(), midPoint.getNorm()};
return distances;
}
/** Compute distance between two line sensors with derivatives.
* @param sensorA line sensor A
/** Compute distances between two line sensors with derivatives.
* @param <T> derivative type
* @param sensorA line sensor A
* @param dateA current date for sensor A
* @param pixelA pixel index for sensor A
* @param sensorB line sensor B
* @param scToBodyA spacecraftToBody transform for sensor A
* @param sensorB line sensor B
* @param dateB current date for sensor B
* @param pixelB pixel index for sensor B
* @param generator generator to use for building {@link DerivativeStructure} instances
* @return distance computing with derivatives
* @exception RuggedException if sensor is unknown
* @see #distanceBetweenLOS(String, AbsoluteDate, int, String, AbsoluteDate, int)
*/
private DerivativeStructure[] distanceBetweenLOSDerivatives(final LineSensor sensorA,
final AbsoluteDate dateA, final int pixelA,
final LineSensor sensorB,
final AbsoluteDate dateB, final int pixelB,
final DSGenerator generator)
throws RuggedException {
//final LineSensor sensorA = getLineSensor(sensorNameA);
//final LineSensor sensorB = getLineSensor(sensorNameB);
// Get sensors's LOS
final FieldVector3D<DerivativeStructure> vA = sensorA.getLOSDerivatives(dateA, pixelA, generator); // V_a : line of sight's vectorA
final FieldVector3D<DerivativeStructure> vB = sensorB.getLOSDerivatives(dateB, pixelB, generator); // V_b
// Get sensors's position. TODO: check if we have to implement getPositionDerivatives() method & CO
final Vector3D sAtmp = sensorA.getPosition(); // S_a : sensorA 's position
final Vector3D sBtmp = sensorB.getPosition(); // S_b
final DerivativeStructure scaleFactor = FieldVector3D.dotProduct(vA.normalize(), vA.normalize()); // V_a.V_a=1
// Build a vector from position vector and a scale factor (equals to 1).
// The vector built will be scaleFactor * sA for example.
final FieldVector3D<DerivativeStructure> sA = new FieldVector3D<DerivativeStructure>(scaleFactor, sAtmp);
final FieldVector3D<DerivativeStructure> sB = new FieldVector3D<DerivativeStructure>(scaleFactor, sBtmp);
// final FieldVector3D<DerivativeStructure> sA = sensorA.getPositionDerivatives(); // S_a : sensorA 's position
// final FieldVector3D<DerivativeStructure> sB = sensorB.getPositionDerivatives(); // S_b
final FieldVector3D<DerivativeStructure> vBase= sB.subtract(sA); // S_b - S_a
final DerivativeStructure svA = FieldVector3D.dotProduct(vBase, vA); // SV_a = (S_b - S_a).V_a
final DerivativeStructure svB = FieldVector3D.dotProduct(vBase, vB); // SV_b = (S_b - S_a).V_b
final DerivativeStructure vAvB = FieldVector3D.dotProduct(vA, vB); // V_a.V_b
// Compute lambda_b = (SV_a * V_a.V_b - SV_b) / (1 + (V_a.V_b)²)
final DerivativeStructure lambdaB = (svA.multiply(vAvB).subtract(svB)).divide(vAvB.pow(2).add(1));
// Compute lambda_a = SV_a + lambdaB * V_a.V_b
final DerivativeStructure lambdaA = vAvB.multiply(lambdaB).add(svA);
final FieldVector3D<DerivativeStructure> mA = sA.add(vA.scalarMultiply(lambdaA)); // M_a = S_a + lambda_a * V_a
final FieldVector3D<DerivativeStructure> mB = sB.add(vB.scalarMultiply(lambdaB)); // M_b = S_b + lambda_b * V_b
final FieldVector3D<DerivativeStructure> vDistance = mB.subtract(mA); // M_b - M_a
// Get square of the euclidean norm
final DerivativeStructure d = vDistance.getNormSq();
return new DerivativeStructure[] {d};
}
/** Estimate the free parameters from two viewing models (A and B)
* @param references reference mappings between two sensors pixels from two models
* and the corresponding computed distance between LOS that
* should ultimately be reached by adjusting selected viewing models parameters
* @param maxEvaluations maximum number of evaluations
* @param parametersConvergenceThreshold convergence threshold on
* normalized parameters (dimensionless, related to parameters scales)
* @param ruggedA rugged instance from viewing model A
* @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 ...)
* @return distances computed, with derivatives, between LOS and to the ground
* @see #distanceBetweenLOS(LineSensor, AbsoluteDate, double, SpacecraftToObservedBody, LineSensor, AbsoluteDate, double)
*/
public Optimum estimateFreeParams2Models(final Collection<SensorToSensorMapping> references,
final int maxEvaluations,
final double parametersConvergenceThreshold,
Rugged ruggedA)
throws RuggedException {
try {
// TODO BEGIN-----------------------
// Verify that createGenerator's construction is ok with the use of two Rugged instance
final List<LineSensor> selectedSensors = new ArrayList<>();
for (final SensorToSensorMapping reference : references) {
selectedSensors.add(getLineSensor(reference.getSensorNameA())); // from ruggedA instance
selectedSensors.add(getLineSensor(reference.getSensorNameB())); // from current ruggedB instance
}
final DSGenerator generator = createGenerator(selectedSensors);
final List<ParameterDriver> selected = generator.getSelected();
if (selected.isEmpty()) {
throw new RuggedException(RuggedMessages.NO_PARAMETERS_SELECTED);
}
// TODO END--------------------------
public <T extends Derivative<T>> T[] distanceBetweenLOSderivatives(
final LineSensor sensorA, final AbsoluteDate dateA, final double pixelA,
final SpacecraftToObservedBody scToBodyA,
final LineSensor sensorB, final AbsoluteDate dateB, final double pixelB,
final DerivativeGenerator<T> generator) {
// get start point (as a normalized value)
final double[] start = new double[selected.size()];
for (int i = 0; i < start.length; ++i) {
start[i] = selected.get(i).getNormalizedValue();
}
// Compute the approximate transforms between spacecraft and observed body
// from Rugged instance A
final Transform scToInertA = scToBodyA.getScToInertial(dateA);
final Transform inertToBodyA = scToBodyA.getInertialToBody(dateA);
final Transform transformScToBodyA = new Transform(dateA, scToInertA, inertToBodyA);
// set up target : distance between two LOS from both viewing models (A and B)
int n = 0;
for (final SensorToSensorMapping reference : references) {
n += reference.getMappings().size();
}
if (n == 0) {
throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS);
}
final double[] target = new double[n];
int k = 0;
for (final SensorToSensorMapping reference : references) {
for (final Double distMeas : reference.getMapDistance()) {
target[k++] = distMeas.doubleValue(); // distances measurements
}
}
// from (current) Rugged instance B
final Transform scToInertB = scToBody.getScToInertial(dateB);
final Transform inertToBodyB = scToBody.getInertialToBody(dateB);
final Transform transformScToBodyB = new Transform(dateB, scToInertB, inertToBodyB);
// prevent parameters to exceed their prescribed bounds
final ParameterValidator validator = params -> {
try {
int i = 0;
for (final ParameterDriver driver : selected) {
// let the parameter handle min/max clipping
driver.setNormalizedValue(params.getEntry(i));
params.setEntry(i++, driver.getNormalizedValue());
}
return params;
} catch (OrekitException oe) {
throw new OrekitExceptionWrapper(oe);
}
};
// Get sensors LOS into local frame
final FieldVector3D<T> vALocal = sensorA.getLOSDerivatives(dateA, pixelA, generator);
final FieldVector3D<T> vBLocal = sensorB.getLOSDerivatives(dateB, pixelB, generator);
// convergence checker
final ConvergenceChecker<LeastSquaresProblem.Evaluation> checker =
(iteration, previous, current) ->
current.getPoint().getLInfDistance(previous.getPoint()) <= parametersConvergenceThreshold;
// Get sensors LOS into body frame
final FieldVector3D<T> vA = transformScToBodyA.transformVector(vALocal); // V_a : line of sight's vectorA
final FieldVector3D<T> vB = transformScToBodyB.transformVector(vBLocal); // V_b : line of sight's vectorB
// model function
final MultivariateJacobianFunction model = point -> {
try {
// Position of sensors into local frame
final Vector3D sAtmp = sensorA.getPosition();
final Vector3D sBtmp = sensorB.getPosition();
// set the current parameters values
int i = 0;
for (final ParameterDriver driver : selected) {
driver.setNormalizedValue(point.getEntry(i++));
// TODO: to be confirmed with the remark done above.
}
final T scaleFactor = FieldVector3D.dotProduct(vA.normalize(), vA.normalize()); // V_a.V_a=1
// compute distance and its partial derivatives
final RealVector value = new ArrayRealVector(target.length);
final RealMatrix jacobian = new Array2DRowRealMatrix(target.length, selected.size());
int l = 0;
for (final SensorToSensorMapping reference : references) {
for (final Map.Entry<SensorPixel, SensorPixel> mapping : reference.getMappings()) {
final SensorPixel spA = mapping.getKey();
final SensorPixel spB = mapping.getValue();
LineSensor lineSensorB = this.getLineSensor(reference.getSensorNameB());
LineSensor lineSensorA = ruggedA.getLineSensor(reference.getSensorNameA());
final AbsoluteDate dateA = lineSensorA.getDate(spA.getLineNumber());
final AbsoluteDate dateB = lineSensorB.getDate(spB.getLineNumber());
final int pixelA = (int)spA.getPixelNumber(); // Note: Rugged don't deal with half-pixel
final int pixelB = (int)spB.getPixelNumber();
final DerivativeStructure[] ilResult =
distanceBetweenLOSDerivatives(reference.getSensorNameA(),
dateA,
pixelA,
reference.getSensorNameB(),
dateB,
pixelB,
generator);
if (ilResult == null) {
// TODO
} else {
// extract the value
value.setEntry(l, ilResult[0].getValue());
// extract the Jacobian
final int[] orders = new int[selected.size()];
for (int m = 0; m < selected.size(); ++m) {
final double scale = selected.get(m).getScale();
orders[m] = 1;
jacobian.setEntry(l, m, ilResult[0].getPartialDerivative(orders) * scale);
orders[m] = 0;
}
}
l += 1; // pass to the next evaluation
// Build a vector from the position and a scale factor (equals to 1).
// The vector built will be scaleFactor * sAtmp for example.
final FieldVector3D<T> sALocal = new FieldVector3D<>(scaleFactor, sAtmp);
final FieldVector3D<T> sBLocal = new FieldVector3D<>(scaleFactor, sBtmp);
}
}
// Get sensors position into body frame
final FieldVector3D<T> sA = transformScToBodyA.transformPosition(sALocal); // S_a : sensorA 's position
final FieldVector3D<T> sB = transformScToBodyB.transformPosition(sBLocal); // S_b : sensorB 's position
// distance result with Jacobian for all reference points
return new Pair<RealVector, RealMatrix>(value, jacobian);
// Compute distance
final FieldVector3D<T> vBase = sB.subtract(sA); // S_b - S_a
final T svA = FieldVector3D.dotProduct(vBase, vA); // SV_a = (S_b - S_a).V_a
final T svB = FieldVector3D.dotProduct(vBase, vB); // SV_b = (S_b - S_a).V_b
final T vAvB = FieldVector3D.dotProduct(vA, vB); // V_a.V_b
// Compute lambda_b = (SV_a * V_a.V_b - SV_b) / (1 - (V_a.V_b)²)
final T lambdaB = (svA.multiply(vAvB).subtract(svB)).divide(vAvB.multiply(vAvB).subtract(1).negate());
// Compute lambda_a = SV_a + lambdaB * V_a.V_b
final T lambdaA = vAvB.multiply(lambdaB).add(svA);
// Compute vector M_a:
final FieldVector3D<T> mA = sA.add(vA.scalarMultiply(lambdaA)); // M_a = S_a + lambda_a * V_a
// Compute vector M_b
final FieldVector3D<T> mB = sB.add(vB.scalarMultiply(lambdaB)); // M_b = S_b + lambda_b * V_b
// Compute vector M_a -> M_B for which distance between LOS is minimum
final FieldVector3D<T> vDistanceMin = mB.subtract(mA); // M_b - M_a
// Compute vector from mid point of vector M_a -> M_B to the ground (corresponds to minimum elevation)
final FieldVector3D<T> midPoint = (mB.add(mA)).scalarMultiply(0.5);
// Get the euclidean norms to compute the minimum distances:
// between LOS
final T dMin = vDistanceMin.getNorm();
// to the ground
final T dCentralBody = midPoint.getNorm();
final T[] ret = MathArrays.buildArray(dMin.getField(), 2);
ret[0] = dMin;
ret[1] = dCentralBody;
return ret;
} catch (RuggedException re) {
throw new RuggedExceptionWrapper(re);
} catch (OrekitException oe) {
throw new OrekitExceptionWrapper(oe);
}
};
// set up the least squares problem
final LeastSquaresProblem problem = new LeastSquaresBuilder().
lazyEvaluation(false).
maxIterations(maxEvaluations).
maxEvaluations(maxEvaluations).
weight(null).
start(start).
target(target).
parameterValidator(validator).
checker(checker).
model(model).
build();
// set up the optimizer
final LeastSquaresOptimizer optimizer = new LevenbergMarquardtOptimizer();
// solve the least squares problem
return optimizer.optimize(problem);
} catch (RuggedExceptionWrapper rew) {
throw rew.getException();
} catch (OrekitExceptionWrapper oew) {
final OrekitException oe = oew.getException();
throw new RuggedException(oe, oe.getSpecifier(), oe.getParts());
}
}
/** Get the mean plane crossing finder for a sensor.
* @param sensorName name of the line sensor
* @param sensorName name of the line sensor
* @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);
......@@ -888,35 +1087,32 @@ public class Rugged {
}
return planeCrossing;
}
/** 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);
}
/** Inverse location of a point with derivatives.
* @param sensorName name of the line sensor
* @param <T> derivative type
* @param sensorName name of the line sensor
* @param point point to localize
* @param minLine minimum line number
* @param maxLine maximum line number
* @param generator generator to use for building {@link DerivativeStructure} instances
* @param generator generator to use for building {@link Derivative} 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
*/
private DerivativeStructure[] inverseLocationDerivatives(final String sensorName,
final GeodeticPoint point,
final int minLine,
final int maxLine,
final DSGenerator generator)
throws RuggedException {
public <T extends Derivative<T>> T[] inverseLocationDerivatives(final String sensorName,
final GeodeticPoint point,
final int minLine,
final int maxLine,
final DerivativeGenerator<T> generator) {
final LineSensor sensor = getLineSensor(sensorName);
......@@ -944,329 +1140,71 @@ public class Rugged {
// fix line by considering the closest pixel exact position and line-of-sight
// (this pixel might point towards a direction slightly above or below the mean sensor plane)
final int lowIndex = FastMath.max(0, FastMath.min(sensor.getNbPixels() - 2, (int) FastMath.floor(coarsePixel)));
final FieldVector3D<DerivativeStructure> lowLOS =
final FieldVector3D<T> lowLOS =
sensor.getLOSDerivatives(crossingResult.getDate(), lowIndex, generator);
final FieldVector3D<DerivativeStructure> highLOS = sensor.getLOSDerivatives(crossingResult.getDate(), lowIndex + 1, generator);
final FieldVector3D<DerivativeStructure> localZ = FieldVector3D.crossProduct(lowLOS, highLOS).normalize();
final DerivativeStructure beta = FieldVector3D.dotProduct(crossingResult.getTargetDirection(), localZ).acos();
final DerivativeStructure s = FieldVector3D.dotProduct(crossingResult.getTargetDirectionDerivative(), localZ);
final DerivativeStructure minusBetaDer = s.divide(s.multiply(s).subtract(1).negate().sqrt());
final DerivativeStructure deltaL = beta.subtract(0.5 * FastMath.PI) .divide(minusBetaDer);
final DerivativeStructure fixedLine = deltaL.add(crossingResult.getLine());
final FieldVector3D<DerivativeStructure> fixedDirection =
new FieldVector3D<DerivativeStructure>(deltaL.getField().getOne(), crossingResult.getTargetDirection(),
deltaL, crossingResult.getTargetDirectionDerivative()).normalize();
final FieldVector3D<T> highLOS = sensor.getLOSDerivatives(crossingResult.getDate(), lowIndex + 1, generator);
final FieldVector3D<T> localZ = FieldVector3D.crossProduct(lowLOS, highLOS).normalize();
final T beta = FieldVector3D.dotProduct(crossingResult.getTargetDirection(), localZ).acos();
final T s = FieldVector3D.dotProduct(crossingResult.getTargetDirectionDerivative(), localZ);
final T minusBetaDer = s.divide(s.multiply(s).subtract(1).negate().sqrt());
final T deltaL = beta.subtract(0.5 * FastMath.PI) .divide(minusBetaDer);
final T fixedLine = deltaL.add(crossingResult.getLine());
final FieldVector3D<T> fixedDirection =
new FieldVector3D<>(deltaL.getField().getOne(), crossingResult.getTargetDirection(),
deltaL, crossingResult.getTargetDirectionDerivative()).normalize();
// fix neighbouring pixels
final AbsoluteDate fixedDate = sensor.getDate(fixedLine.getValue());
final FieldVector3D<DerivativeStructure> fixedX = sensor.getLOSDerivatives(fixedDate, lowIndex, generator);
final FieldVector3D<DerivativeStructure> fixedZ = FieldVector3D.crossProduct(fixedX, sensor.getLOSDerivatives(fixedDate, lowIndex + 1, generator));
final FieldVector3D<DerivativeStructure> fixedY = FieldVector3D.crossProduct(fixedZ, fixedX);
final FieldVector3D<T> fixedX = sensor.getLOSDerivatives(fixedDate, lowIndex, generator);
final FieldVector3D<T> fixedZ = FieldVector3D.crossProduct(fixedX, sensor.getLOSDerivatives(fixedDate, lowIndex + 1, generator));
final FieldVector3D<T> fixedY = FieldVector3D.crossProduct(fixedZ, fixedX);
// fix pixel
final DerivativeStructure hY = FieldVector3D.dotProduct(highLOS, fixedY);
final DerivativeStructure hX = FieldVector3D.dotProduct(highLOS, fixedX);
final DerivativeStructure pixelWidth = hY.atan2(hX);
final DerivativeStructure fY = FieldVector3D.dotProduct(fixedDirection, fixedY);
final DerivativeStructure fX = FieldVector3D.dotProduct(fixedDirection, fixedX);
final DerivativeStructure alpha = fY.atan2(fX);
final DerivativeStructure fixedPixel = alpha.divide(pixelWidth).add(lowIndex);
return new DerivativeStructure[] {
fixedLine, fixedPixel
};
}
/** Estimate the free parameters in viewing model to match specified sensor
* to ground mappings.
* <p>
* This method is typically used for calibration of on-board sensor parameters,
* like rotation angles polynomial coefficients.
* </p>
* <p>
* Before using this method, the {@link ParameterDriver viewing model
* parameters} retrieved by calling the {@link
* LineSensor#getParametersDrivers() getParametersDrivers()}
* method on the desired sensors must be configured. The parameters that should
* be estimated must have their {@link ParameterDriver#setSelected(boolean)
* selection status} set to {@link true} whereas the parameters that should retain
* their current value must have their {@link ParameterDriver#setSelected(boolean)
* selection status} set to {@link false}. If needed, the {@link
* ParameterDriver#setValue(double) value} of the estimated/selected parameters
* can also be changed before calling the method, as this value will serve as the
* initial value in the estimation process.
* </p>
* <p>
* The method solves a least-squares problem to minimize the residuals between test
* locations and the reference mappings by adjusting the selected viewing models
* parameters.
* </p>
* <p>
* The estimated parameters can be retrieved after the method completes by calling
* again the {@link LineSensor#getParametersDrivers() getParametersDrivers()}
* method on the desired sensors and checking the updated values of the parameters.
* In fact, as the values of the parameters are already updated by this method, if
* users want to use the updated values immediately to perform new direct/inverse
* locations, they can do so without looking at the parameters: the viewing models
* are already aware of the updated parameters.
* </p>
* @param references reference mappings between sensors pixels and ground point that
* should ultimately be reached by adjusting selected viewing models parameters
* @param maxEvaluations maximum number of evaluations
* @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<SensorToGroundMapping> references,
final int maxEvaluations,
final double parametersConvergenceThreshold)
throws RuggedException {
try {
final List<LineSensor> selectedSensors = new ArrayList<>();
for (final SensorToGroundMapping reference : references) {
selectedSensors.add(getLineSensor(reference.getSensorName()));
}
final DSGenerator generator = createGenerator(selectedSensors);
final List<ParameterDriver> selected = generator.getSelected();
if (selected.isEmpty()) {
throw new RuggedException(RuggedMessages.NO_PARAMETERS_SELECTED);
}
// get start point (as a normalized value)
final double[] start = new double[selected.size()];
for (int i = 0; i < start.length; ++i) {
start[i] = selected.get(i).getNormalizedValue();
}
// set up target in sensor domain
int n = 0;
for (final SensorToGroundMapping reference : references) {
n += reference.getMappings().size();
}
if (n == 0) {
throw new RuggedException(RuggedMessages.NO_REFERENCE_MAPPINGS);
}
final double[] target = new double[2 * n];
double min = Double.POSITIVE_INFINITY;
double max = Double.NEGATIVE_INFINITY;
int k = 0;
for (final SensorToGroundMapping reference : references) {
for (final Map.Entry<SensorPixel, GeodeticPoint> mapping : reference.getMappings()) {
final SensorPixel sp = mapping.getKey();
target[k++] = sp.getLineNumber();
target[k++] = sp.getPixelNumber();
min = FastMath.min(min, sp.getLineNumber());
max = FastMath.max(max, sp.getLineNumber());
}
}
final int minLine = (int) FastMath.floor(min - ESTIMATION_LINE_RANGE_MARGIN);
final int maxLine = (int) FastMath.ceil(max - ESTIMATION_LINE_RANGE_MARGIN);
// prevent parameters to exceed their prescribed bounds
final ParameterValidator validator = params -> {
try {
int i = 0;
for (final ParameterDriver driver : selected) {
// let the parameter handle min/max clipping
driver.setNormalizedValue(params.getEntry(i));
params.setEntry(i++, driver.getNormalizedValue());
}
return params;
} catch (OrekitException oe) {
throw new OrekitExceptionWrapper(oe);
}
};
// convergence checker
final ConvergenceChecker<LeastSquaresProblem.Evaluation> checker =
(iteration, previous, current) ->
current.getPoint().getLInfDistance(previous.getPoint()) <= parametersConvergenceThreshold;
final T hY = FieldVector3D.dotProduct(highLOS, fixedY);
final T hX = FieldVector3D.dotProduct(highLOS, fixedX);
final T pixelWidth = hY.atan2(hX);
final T fY = FieldVector3D.dotProduct(fixedDirection, fixedY);
final T fX = FieldVector3D.dotProduct(fixedDirection, fixedX);
final T alpha = fY.atan2(fX);
final T fixedPixel = alpha.divide(pixelWidth).add(lowIndex);
final T[] ret = MathArrays.buildArray(fixedPixel.getField(), 2);
ret[0] = fixedLine;
ret[1] = fixedPixel;
return ret;
// model function
final MultivariateJacobianFunction model = point -> {
try {
// set the current parameters values
int i = 0;
for (final ParameterDriver driver : selected) {
driver.setNormalizedValue(point.getEntry(i++));
}
// compute inverse loc and its partial derivatives
final RealVector value = new ArrayRealVector(target.length);
final RealMatrix jacobian = new Array2DRowRealMatrix(target.length, selected.size());
int l = 0;
for (final SensorToGroundMapping reference : references) {
for (final Map.Entry<SensorPixel, GeodeticPoint> mapping : reference.getMappings()) {
final GeodeticPoint gp = mapping.getValue();
final DerivativeStructure[] ilResult =
inverseLocationDerivatives(reference.getSensorName(),
gp, minLine, maxLine, generator);
if (ilResult == null) {
value.setEntry(l, minLine - 100.0); // arbitrary line far away
value.setEntry(l + 1, -100.0); // arbitrary pixel far away
} else {
// extract the value
value.setEntry(l, ilResult[0].getValue());
value.setEntry(l + 1, ilResult[1].getValue());
// extract the Jacobian
final int[] orders = new int[selected.size()];
for (int m = 0; m < selected.size(); ++m) {
final double scale = selected.get(m).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;
}
}
l += 2;
}
}
// 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);
}
};
// set up the least squares problem
final LeastSquaresProblem problem = new LeastSquaresBuilder().
lazyEvaluation(false).
maxIterations(maxEvaluations).
maxEvaluations(maxEvaluations).
weight(null).
start(start).
target(target).
parameterValidator(validator).
checker(checker).
model(model).
build();
// set up the optimizer
//final LeastSquaresOptimizer optimizer = new LevenbergMarquardtOptimizer();
final LeastSquaresOptimizer optimizer = new GaussNewtonOptimizer().withDecomposition(GaussNewtonOptimizer.Decomposition.QR);
// solve the least squares problem
return optimizer.optimize(problem);
} catch (RuggedExceptionWrapper rew) {
throw rew.getException();
} catch (OrekitExceptionWrapper oew) {
final OrekitException oe = oew.getException();
throw new RuggedException(oe, oe.getSpecifier(), oe.getParts());
}
}
/** Create the generator for {@link DerivativeStructure} instances.
* @param selectedSensors sensors referencing the parameters drivers
* @return a new generator
* @exception RuggedException if several parameters with the same name exist
*/
private DSGenerator createGenerator(final List<LineSensor> selectedSensors)
throws RuggedException {
// we are more stringent than Orekit orbit determination:
// we do not allow different parameters with the same name
final Set<String> names = new HashSet<>();
for (final LineSensor sensor : selectedSensors) {
sensor.getParametersDrivers().forEach(driver -> {
if (names.contains(driver.getName())) {
throw new RuggedExceptionWrapper(new RuggedException(RuggedMessages.DUPLICATED_PARAMETER_NAME,
driver.getName()));
}
names.add(driver.getName());
});
}
// set up generator list and map
final List<ParameterDriver> selected = new ArrayList<>();
final Map<String, Integer> map = new HashMap<>();
for (final LineSensor sensor : selectedSensors) {
sensor.
getParametersDrivers().
filter(driver -> driver.isSelected()).
forEach(driver -> {
selected.add(driver);
map.put(driver.getName(), map.size());
});
}
return new DSGenerator() {
/** {@inheritDoc} */
@Override
public List<ParameterDriver> getSelected() {
return selected;
}
/** {@inheritDoc} */
@Override
public DerivativeStructure constant(final double value) {
return new DerivativeStructure(map.size(), 1, value);
}
/** {@inheritDoc} */
@Override
public DerivativeStructure variable(final ParameterDriver driver) {
final Integer index = map.get(driver.getName());
if (index == null) {
return constant(driver.getValue());
} else {
return new DerivativeStructure(map.size(), 1, index.intValue(), driver.getValue());
}
}
};
}
/** 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);
......@@ -1274,4 +1212,11 @@ public class Rugged {
return sensor;
}
/** Get converter between spacecraft and body.
* @return the scToBody
* @since 2.0
*/
public SpacecraftToObservedBody getScToBody() {
return scToBody;
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -16,9 +16,6 @@
*/
package org.orekit.rugged.api;
import org.hipparchus.exception.LocalizedCoreFormats;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import java.io.IOException;
import java.io.InputStream;
import java.io.ObjectInputStream;
......@@ -28,14 +25,15 @@ import java.util.ArrayList;
import java.util.Collections;
import java.util.List;
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;
import org.orekit.propagation.SpacecraftState;
import org.orekit.propagation.sampling.OrekitFixedStepHandler;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedInternalError;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.intersection.BasicScanAlgorithm;
import org.orekit.rugged.intersection.ConstantElevationAlgorithm;
......@@ -44,6 +42,7 @@ import org.orekit.rugged.intersection.IntersectionAlgorithm;
import org.orekit.rugged.intersection.duvenhage.DuvenhageAlgorithm;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.raster.TileUpdater;
import org.orekit.rugged.refraction.AtmosphericRefraction;
import org.orekit.rugged.utils.ExtendedEllipsoid;
import org.orekit.rugged.utils.SpacecraftToObservedBody;
import org.orekit.time.AbsoluteDate;
......@@ -84,6 +83,7 @@ import org.orekit.utils.TimeStampedPVCoordinates;
* @see <a href="https://en.wikipedia.org/wiki/Builder_pattern">Builder pattern (wikipedia)</a>
* @see <a href="https://en.wikipedia.org/wiki/Fluent_interface">Fluent interface (wikipedia)</a>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class RuggedBuilder {
......@@ -96,7 +96,7 @@ public class RuggedBuilder {
/** Updater used to load Digital Elevation Model tiles. */
private TileUpdater tileUpdater;
/** Constant elevation over ellipsoid.
/** Constant elevation over ellipsoid (m).
* used only with {@link AlgorithmId#CONSTANT_ELEVATION_OVER_ELLIPSOID. */
private double constantElevation;
......@@ -109,10 +109,10 @@ public class RuggedBuilder {
/** End of search time span. */
private AbsoluteDate maxDate;
/** Step to use for inertial frame to body frame transforms cache computations. */
/** Step to use for inertial frame to body frame transforms cache computations (s). */
private double tStep;
/** OvershootTolerance tolerance in seconds allowed for {@code minDate} and {@code maxDate} overshooting. */
/** OvershootTolerance tolerance in seconds allowed for {@code minDate} and {@code maxDate} overshooting (s). */
private double overshootTolerance;
/** Inertial frame for position/velocity/attitude. */
......@@ -139,10 +139,10 @@ public class RuggedBuilder {
/** Propagator for position/velocity/attitude. */
private Propagator pvaPropagator;
/** Step to use for inertial/Earth/spacraft transforms interpolations. */
/** Step to use for inertial/Earth/spacecraft transforms interpolations (s). */
private double iStep;
/** Number of points to use for inertial/Earth/spacraft transforms interpolations. */
/** Number of points to use for inertial/Earth/spacecraft transforms interpolations. */
private int iN;
/** Converter between spacecraft and body. */
......@@ -154,9 +154,15 @@ public class RuggedBuilder {
/** Flag for aberration of light correction. */
private boolean aberrationOfLightCorrection;
/** Atmospheric refraction to use for line of sight correction. */
private AtmosphericRefraction atmosphericRefraction;
/** Sensors. */
private final List<LineSensor> sensors;
/** Rugged name. */
private String name;
/** Create a non-configured builder.
* <p>
* The builder <em>must</em> be configured before calling the
......@@ -165,42 +171,35 @@ public class RuggedBuilder {
* </p>
*/
public RuggedBuilder() {
sensors = new ArrayList<LineSensor>();
sensors = new ArrayList<>();
constantElevation = Double.NaN;
lightTimeCorrection = true;
aberrationOfLightCorrection = true;
name = "Rugged";
}
/** 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 ellipsoid 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()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setEllipsoid(final OneAxisEllipsoid ellipsoid)
throws RuggedException {
// CHECKSTYLE: resume HiddenField check
this.ellipsoid = new ExtendedEllipsoid(ellipsoid.getEquatorialRadius(),
ellipsoid.getFlattening(),
ellipsoid.getBodyFrame());
public RuggedBuilder setEllipsoid(final OneAxisEllipsoid newEllipsoid) {
this.ellipsoid = new ExtendedEllipsoid(newEllipsoid.getEquatorialRadius(),
newEllipsoid.getFlattening(),
newEllipsoid.getBodyFrame());
checkFramesConsistency();
return this;
}
......@@ -214,6 +213,22 @@ public class RuggedBuilder {
return ellipsoid;
}
/** Get the Rugged name.
* @return the Rugged name
* @since 2.0
*/
public String getName() {
return name;
}
/** Set the Rugged name.
* @param name the Rugged name
* @since 2.0
*/
public void setName(final String name) {
this.name = name;
}
/** Set the algorithm to use for Digital Elevation Model intersection.
* <p>
* Note that some algorithms require specific other methods to be called too:
......@@ -231,16 +246,14 @@ public class RuggedBuilder {
* IGNORE_DEM_USE_ELLIPSOID} does not require
* any methods tobe called.</li>
* </ul>
* </p>
* @param algorithmID identifier of algorithm to use for Digital Elevation Model intersection
*
* @param newAlgorithmId identifier of algorithm to use for Digital Elevation Model intersection
* @return the builder instance
* @see #setDigitalElevationModel(TileUpdater, int)
* @see #getAlgorithm()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setAlgorithm(final AlgorithmId algorithmID) {
// CHECKSTYLE: resume HiddenField check
this.algorithmID = algorithmID;
public RuggedBuilder setAlgorithm(final AlgorithmId newAlgorithmId) {
this.algorithmID = newAlgorithmId;
return this;
}
......@@ -262,18 +275,16 @@ public class RuggedBuilder {
* or it can be called with an updater set to {@code null}. For all other
* algorithms, the updater must be properly configured.
* </p>
* @param tileUpdater updater used to load Digital Elevation Model tiles
* @param maxCachedTiles maximum number of tiles stored in the cache
* @param newTileUpdater updater used to load Digital Elevation Model tiles
* @param newMaxCachedTiles maximum number of tiles stored in the cache
* @return the builder instance
* @see #setAlgorithm(AlgorithmId)
* @see #getTileUpdater()
* @see #getMaxCachedTiles()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setDigitalElevationModel(final TileUpdater tileUpdater, final int maxCachedTiles) {
// CHECKSTYLE: resume HiddenField check
this.tileUpdater = tileUpdater;
this.maxCachedTiles = maxCachedTiles;
public RuggedBuilder setDigitalElevationModel(final TileUpdater newTileUpdater, final int newMaxCachedTiles) {
this.tileUpdater = newTileUpdater;
this.maxCachedTiles = newMaxCachedTiles;
return this;
}
......@@ -293,15 +304,13 @@ public class RuggedBuilder {
* AlgorithmId#CONSTANT_ELEVATION_OVER_ELLIPSOID CONSTANT_ELEVATION_OVER_ELLIPSOID}.
* If it is called for another algorithm, the elevation set here will be ignored.
* </p>
* @param constantElevation constant elevation to use
* @param newConstantElevation constant elevation to use (m)
* @return the builder instance
* @see #setAlgorithm(AlgorithmId)
* @see #getConstantElevation()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setConstantElevation(final double constantElevation) {
// CHECKSTYLE: resume HiddenField check
this.constantElevation = constantElevation;
public RuggedBuilder setConstantElevation(final double newConstantElevation) {
this.constantElevation = newConstantElevation;
return this;
}
......@@ -331,10 +340,10 @@ public class RuggedBuilder {
* or {@link #setTrajectory(double, int, CartesianDerivativesFilter, AngularDerivativesFilter, Propagator)}
* but should <em>not</em> be mixed with {@link #setTrajectoryAndTimeSpan(InputStream)}.
* </p>
* @param minDate start of search time span
* @param maxDate end of search time span
* @param tStep step to use for inertial frame to body frame transforms cache computations
* @param overshootTolerance tolerance in seconds allowed for {@code minDate} and {@code maxDate} overshooting
* @param newMinDate start of search time span
* @param newMaxDate end of search time span
* @param newTstep step to use for inertial frame to body frame transforms cache computations (s)
* @param newOvershootTolerance tolerance in seconds allowed for {@code minDate} and {@code maxDate} overshooting (s)
* @return the builder instance
* @see #setTrajectoryAndTimeSpan(InputStream)
* @see #getMinDate()
......@@ -342,14 +351,12 @@ public class RuggedBuilder {
* @see #getTStep()
* @see #getOvershootTolerance()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setTimeSpan(final AbsoluteDate minDate, final AbsoluteDate maxDate,
final double tStep, final double overshootTolerance) {
// CHECKSTYLE: resume HiddenField check
this.minDate = minDate;
this.maxDate = maxDate;
this.tStep = tStep;
this.overshootTolerance = overshootTolerance;
public RuggedBuilder setTimeSpan(final AbsoluteDate newMinDate, final AbsoluteDate newMaxDate,
final double newTstep, final double newOvershootTolerance) {
this.minDate = newMinDate;
this.maxDate = newMaxDate;
this.tStep = newTstep;
this.overshootTolerance = newOvershootTolerance;
this.scToBody = null;
return this;
}
......@@ -392,7 +399,7 @@ public class RuggedBuilder {
* <em>must</em> be used together with the {@link #setTimeSpan(AbsoluteDate, AbsoluteDate, double, double)}
* but should <em>not</em> be mixed with {@link #setTrajectoryAndTimeSpan(InputStream)}.
* </p>
* @param inertialFrame inertial frame used for spacecraft positions/velocities/quaternions
* @param inertialFrameId inertial frame Id used for spacecraft positions/velocities/quaternions
* @param positionsVelocities satellite position and velocity (m and m/s in inertial frame)
* @param pvInterpolationNumber number of points to use for position/velocity interpolation
* @param pvFilter filter for derivatives from the sample to use in position/velocity interpolation
......@@ -400,7 +407,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)
......@@ -412,13 +418,13 @@ public class RuggedBuilder {
* @see #getAInterpolationNumber()
* @see #getAFilter()
*/
public RuggedBuilder setTrajectory(final InertialFrameId inertialFrame,
public RuggedBuilder setTrajectory(final InertialFrameId inertialFrameId,
final List<TimeStampedPVCoordinates> positionsVelocities, final int pvInterpolationNumber,
final CartesianDerivativesFilter pvFilter,
final List<TimeStampedAngularCoordinates> quaternions, final int aInterpolationNumber,
final AngularDerivativesFilter aFilter)
throws RuggedException {
return setTrajectory(selectInertialFrame(inertialFrame),
final AngularDerivativesFilter aFilter) {
return setTrajectory(selectInertialFrame(inertialFrameId),
positionsVelocities, pvInterpolationNumber, pvFilter,
quaternions, aInterpolationNumber, aFilter);
}
......@@ -452,6 +458,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;
......@@ -472,8 +479,8 @@ public class RuggedBuilder {
* <em>must</em> be used together with the {@link #setTimeSpan(AbsoluteDate, AbsoluteDate, double, double)}
* but should <em>not</em> be mixed with {@link #setTrajectoryAndTimeSpan(InputStream)}.
* </p>
* @param interpolationStep step to use for inertial/Earth/spacraft transforms interpolations
* @param interpolationNumber number of points to use for inertial/Earth/spacraft transforms interpolations
* @param interpolationStep step to use for inertial/Earth/spacecraft transforms interpolations (s)
* @param interpolationNumber number of points to use for inertial/Earth/spacecraft transforms interpolations
* @param pvFilter filter for derivatives from the sample to use in position/velocity interpolation
* @param aFilter filter for derivatives from the sample to use in attitude interpolation
* @param propagator global propagator
......@@ -566,15 +573,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;
......@@ -593,6 +598,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) {
......@@ -615,7 +621,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)
......@@ -623,7 +628,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);
......@@ -633,23 +638,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()");
......@@ -669,7 +670,6 @@ public class RuggedBuilder {
throw new RuggedException(RuggedMessages.UNINITIALIZED_CONTEXT, "RuggedBuilder.setTrajectory()");
}
}
}
/** Create a transform interpolator from positions and quaternions lists.
......@@ -686,8 +686,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,
......@@ -697,8 +695,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,
......@@ -713,13 +711,12 @@ public class RuggedBuilder {
* @param maxDate end of search time span
* @param tStep step to use for inertial frame to body frame transforms cache computations
* @param overshootTolerance tolerance in seconds allowed for {@code minDate} and {@code maxDate} overshooting
* @param interpolationStep step to use for inertial/Earth/spacraft transforms interpolations
* @param interpolationNumber number of points of to use for inertial/Earth/spacraft transforms interpolations
* @param interpolationStep step to use for inertial/Earth/spacecraft transforms interpolations
* @param interpolationNumber number of points of to use for inertial/Earth/spacecraft transforms interpolations
* @param pvFilter filter for derivatives from the sample to use in position/velocity interpolation
* @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,
......@@ -727,46 +724,29 @@ public class RuggedBuilder {
final double interpolationStep, final int interpolationNumber,
final CartesianDerivativesFilter pvFilter,
final AngularDerivativesFilter aFilter,
final Propagator propagator)
throws RuggedException {
try {
// 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 init(final SpacecraftState s0, final AbsoluteDate t) {
}
/** {@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));
}
final Propagator propagator) {
// extract position/attitude samples from propagator
final List<TimeStampedPVCoordinates> positionsVelocities =
new ArrayList<>();
final List<TimeStampedAngularCoordinates> quaternions =
new ArrayList<>();
propagator.getMultiplexer().add(interpolationStep,
currentState -> {
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);
propagator.propagate(minDate.shiftedBy(-interpolationStep), maxDate.shiftedBy(interpolationStep));
} catch (OrekitException pe) {
throw new RuggedException(pe, pe.getSpecifier(), pe.getParts());
}
// 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.
......@@ -778,16 +758,14 @@ public class RuggedBuilder {
* a parameter set to {@code true}). Not compensating it is mainly useful
* for validation purposes against system that do not compensate it.
* </p>
* @param lightTimeCorrection if true, the light travel time between ground
* @param newLightTimeCorrection if true, the light travel time between ground
* and spacecraft is compensated for more accurate location
* @return the builder instance
* @see #setAberrationOfLightCorrection(boolean)
* @see #getLightTimeCorrection()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setLightTimeCorrection(final boolean lightTimeCorrection) {
// CHECKSTYLE: resume HiddenField check
this.lightTimeCorrection = lightTimeCorrection;
public RuggedBuilder setLightTimeCorrection(final boolean newLightTimeCorrection) {
this.lightTimeCorrection = newLightTimeCorrection;
return this;
}
......@@ -812,16 +790,14 @@ public class RuggedBuilder {
* compensate it or when the pixels line of sight already include the
* correction.
* </p>
* @param aberrationOfLightCorrection if true, the aberration of light
* @param newAberrationOfLightCorrection if true, the aberration of light
* is corrected for more accurate location
* @return the builder instance
* @see #setLightTimeCorrection(boolean)
* @see #getAberrationOfLightCorrection()
*/
// CHECKSTYLE: stop HiddenField check
public RuggedBuilder setAberrationOfLightCorrection(final boolean aberrationOfLightCorrection) {
// CHECKSTYLE: resume HiddenField check
this.aberrationOfLightCorrection = aberrationOfLightCorrection;
public RuggedBuilder setAberrationOfLightCorrection(final boolean newAberrationOfLightCorrection) {
this.aberrationOfLightCorrection = newAberrationOfLightCorrection;
return this;
}
......@@ -833,6 +809,30 @@ public class RuggedBuilder {
return aberrationOfLightCorrection;
}
/** Set atmospheric refraction for line of sight correction.
* <p>
* This method sets an atmospheric refraction model to be used between
* spacecraft and ground for the correction of intersected points on ground.
* Compensating for the effect of atmospheric refraction improves location
* accuracy.
* </p>
* @param newAtmosphericRefraction the atmospheric refraction model to be used for more accurate location
* @return the builder instance
* @see #getRefractionCorrection()
*/
public RuggedBuilder setRefractionCorrection(final AtmosphericRefraction newAtmosphericRefraction) {
this.atmosphericRefraction = newAtmosphericRefraction;
return this;
}
/** Get the atmospheric refraction model.
* @return atmospheric refraction model
* @see #setRefractionCorrection(AtmosphericRefraction)
*/
public AtmosphericRefraction getRefractionCorrection() {
return atmosphericRefraction;
}
/** Set up line sensor model.
* @param lineSensor line sensor model
* @return the builder instance
......@@ -860,14 +860,11 @@ 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 {
private static Frame selectInertialFrame(final InertialFrameId inertialFrameId) {
try {
// set up the inertial frame
switch (inertialFrameId) {
// set up the inertial frame
switch (inertialFrameId) {
case GCRF :
return FramesFactory.getGCRF();
case EME2000 :
......@@ -880,25 +877,18 @@ public class RuggedBuilder {
return FramesFactory.getVeis1950();
default :
// this should never happen
throw RuggedException.createInternalError(null);
}
} catch (OrekitException oe) {
throw new RuggedException(oe, oe.getSpecifier(), oe.getParts().clone());
throw new RuggedInternalError(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 {
private static Frame selectBodyRotatingFrame(final BodyRotatingFrameId bodyRotatingFrame) {
try {
// set up the rotating frame
switch (bodyRotatingFrame) {
// set up the rotating frame
switch (bodyRotatingFrame) {
case ITRF :
return FramesFactory.getITRF(IERSConventions.IERS_2010, true);
case ITRF_EQUINOX :
......@@ -907,12 +897,8 @@ public class RuggedBuilder {
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());
throw new RuggedInternalError(null);
}
}
/** Select ellipsoid.
......@@ -924,19 +910,25 @@ public class RuggedBuilder {
// set up the ellipsoid
switch (ellipsoidID) {
case GRS80 :
return new OneAxisEllipsoid(6378137.0, 1.0 / 298.257222101, bodyFrame);
case WGS84 :
return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS,
Constants.WGS84_EARTH_FLATTENING,
bodyFrame);
case IERS96 :
return new OneAxisEllipsoid(6378136.49, 1.0 / 298.25645, bodyFrame);
case IERS2003 :
return new OneAxisEllipsoid(6378136.6, 1.0 / 298.25642, bodyFrame);
default :
// this should never happen
throw RuggedException.createInternalError(null);
case GRS80 :
return new OneAxisEllipsoid(Constants.GRS80_EARTH_EQUATORIAL_RADIUS,
Constants.GRS80_EARTH_FLATTENING,
bodyFrame);
case WGS84 :
return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS,
Constants.WGS84_EARTH_FLATTENING,
bodyFrame);
case IERS96 :
return new OneAxisEllipsoid(Constants.IERS96_EARTH_EQUATORIAL_RADIUS,
Constants.IERS96_EARTH_FLATTENING,
bodyFrame);
case IERS2003 :
return new OneAxisEllipsoid(Constants.IERS2003_EARTH_EQUATORIAL_RADIUS,
Constants.IERS2003_EARTH_FLATTENING,
bodyFrame);
default :
// this should never happen
throw new RuggedInternalError(null);
}
}
......@@ -954,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 new RuggedInternalError(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()");
}
......@@ -991,7 +981,6 @@ public class RuggedBuilder {
}
createInterpolatorIfNeeded();
return new Rugged(createAlgorithm(algorithmID, tileUpdater, maxCachedTiles, constantElevation), ellipsoid,
lightTimeCorrection, aberrationOfLightCorrection, scToBody, sensors);
lightTimeCorrection, aberrationOfLightCorrection, atmosphericRefraction, scToBody, sensors, name);
}
}
/* Copyright 2013-2016 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.
* CS licenses this file to You under the Apache License, Version 2.0
* (the "License"); you may not use this file except in compliance with
* the License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
package org.orekit.rugged.api;
import java.util.ArrayList;
import java.util.Collection;
import java.util.Collections;
import java.util.IdentityHashMap;
import java.util.Map;
import java.util.Set;
import org.orekit.rugged.linesensor.SensorPixel;
/** Container for mapping between sensor A pixels and sensor B pixels
* and storing distance between the two LOS computed with @link {@link Rugged#distanceBetweenLOS(
* String, org.orekit.time.AbsoluteDate, int, String, org.orekit.time.AbsoluteDate, int)}
* @author Lucie LabatAllee
* @since 2.0
*/
public class SensorToSensorMapping {
/** Name of the sensors to which mapping applies. */
private final String sensorNameA;
private final String sensorNameB;
/** Mapping from sensor A to sensor B. */
private final Map<SensorPixel, SensorPixel> sensorToSensor;
/** Distance between two LOS */
private final Collection<Double> mapDistance;
/** Build a new instance.
* @param sensorNameA name of the sensor A to which mapping applies
* @param sensorNameB name of the sensor B to which mapping applies
*/
public SensorToSensorMapping(final String sensorNameA, final String sensorNameB) {
this.sensorNameA = sensorNameA;
this.sensorNameB = sensorNameB;
this.sensorToSensor = new IdentityHashMap<>();
this.mapDistance = new ArrayList<Double>();
}
/** Get the name of the sensor A to which mapping applies.
* @return name of the sensor A to which mapping applies
*/
public String getSensorNameA() {
return sensorNameA;
}
/** Get the name of the sensor B to which mapping applies.
* @return name of the sensor B to which mapping applies
*/
public String getSensorNameB() {
return sensorNameB;
}
/** Add a mapping between one sensor A pixel to one sensor B pixel and computed distance between both LOS
* @param pixelA sensor A pixel
* @param pixelB sensor B pixel corresponding to the sensor A pixel
*/
public void addMapping(final SensorPixel pixelA, final SensorPixel pixelB, final double distance) {
sensorToSensor.put(pixelA, pixelB);
mapDistance.add(distance);
}
/** Get all the mapping entries.
* @return an unmodifiable view of all mapping entries
*/
public Set<Map.Entry<SensorPixel, SensorPixel>> getMappings() {
return Collections.unmodifiableSet(sensorToSensor.entrySet());
}
/**
* @return the mapDistance
*/
public Collection<Double> getMapDistance() {
return mapDistance;
}
}
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
* (the "License"); you may not use this file except in compliance with
* the License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
/**
*
* This package provides the principal class of Rugged library API, as well as
* the builder for Rugged instances.
*
* @author Luc Maisonobe
* @author Guylaine Prat
*
*/
package org.orekit.rugged.api;
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -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;
......@@ -49,6 +48,7 @@ import org.orekit.time.TimeScalesFactory;
/**
* Dump data class.
* @author Luc Maisonobe
* @author Guylaine Prat
*/
class Dump {
......@@ -75,8 +75,8 @@ class Dump {
*/
Dump(final PrintWriter writer) {
this.writer = writer;
this.tiles = new ArrayList<DumpedTileData>();
this.sensors = new ArrayList<DumpedSensorData>();
this.tiles = new ArrayList<>();
this.sensors = new ArrayList<>();
this.algorithmDumped = false;
this.ellipsoidDumped = false;
this.tranformsDumped = null;
......@@ -145,33 +145,33 @@ class Dump {
/** Dump a direct location computation.
* @param date date of the location
* @param position pixel position in spacecraft frame
* @param sensorPosition sensor position in spacecraft frame
* @param los normalized line-of-sight in spacecraft frame
* @param lightTimeCorrection flag for light time correction
* @param aberrationOfLightCorrection flag for aberration of light correction
* @exception RuggedException if date cannot be converted to UTC
* @param refractionCorrection flag for refraction correction
*/
public void dumpDirectLocation(final AbsoluteDate date, final Vector3D position, final Vector3D los,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection)
throws RuggedException {
public void dumpDirectLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection,
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%n",
"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),
position.getX(), position.getY(), position.getZ(),
sensorPosition.getX(), sensorPosition.getY(), sensorPosition.getZ(),
los.getX(), los.getY(), los.getZ(),
lightTimeCorrection, aberrationOfLightCorrection);
lightTimeCorrection, aberrationOfLightCorrection, refractionCorrection);
}
/** 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",
gp.getLatitude(), gp.getLongitude(), gp.getAltitude());
} else {
writer.format(Locale.US, "direct location result: NULL");
}
}
......@@ -182,17 +182,19 @@ class Dump {
* @param maxLine maximum line number
* @param lightTimeCorrection flag for light time correction
* @param aberrationOfLightCorrection flag for aberration of light correction
* @param refractionCorrection flag for refraction correction
*/
public void dumpInverseLocation(final LineSensor sensor, final GeodeticPoint point,
final int minLine, final int maxLine,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection) {
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection,
final boolean refractionCorrection) {
final DumpedSensorData ds = getSensorData(sensor);
writer.format(Locale.US,
"inverse location: sensorName %s latitude %22.15e longitude %22.15e elevation %22.15e minLine %d maxLine %d lightTime %b aberration %b%n",
"inverse location: sensorName %s latitude %22.15e longitude %22.15e elevation %22.15e minLine %d maxLine %d lightTime %b aberration %b refraction %b %n",
ds.getDumpName(),
point.getLatitude(), point.getLongitude(), point.getAltitude(),
minLine, maxLine,
lightTimeCorrection, aberrationOfLightCorrection);
lightTimeCorrection, aberrationOfLightCorrection, refractionCorrection);
}
/** Dump an inverse location result.
......@@ -203,6 +205,8 @@ class Dump {
writer.format(Locale.US,
"inverse location result: lineNumber %22.15e pixelNumber %22.15e%n",
pixel.getLineNumber(), pixel.getPixelNumber());
} else {
writer.format(Locale.US, "inverse location result: NULL");
}
}
......@@ -211,11 +215,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();
......@@ -241,10 +243,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);
}
......@@ -253,10 +253,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);
}
......@@ -264,10 +262,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);
}
......@@ -343,18 +339,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.
......@@ -496,46 +486,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);
public void setMeanPlane(final SensorMeanPlaneCrossing meanPlane) {
}
} catch (RuggedExceptionWrapper rew) {
throw rew.getException();
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 RuggedInternalError(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);
}
}
......@@ -543,10 +528,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>>();
......@@ -567,10 +550,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) {
......
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -42,11 +42,15 @@ import org.orekit.time.AbsoluteDate;
* time, so user code should not rely on it.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class DumpManager {
/** Dump file (default initial value is null, i.e. nothing is dumped). */
private static final ThreadLocal<Dump> DUMP = new ThreadLocal<Dump>();
private static final ThreadLocal<Dump> DUMP = new ThreadLocal<>();
/** Boolean to check if the dump is suspended. */
private static boolean isSuspended = false;
/** Private constructor for utility class.
*/
......@@ -56,10 +60,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 +75,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);
......@@ -84,11 +85,44 @@ public class DumpManager {
}
}
/** Suspend the dump.
* In case the dump is already suspended, keep the previous status in order to
* correctly deal the resume stage.
* @return a flag to tell if the dump is already suspended (true; false otherwise)
*/
public static Boolean suspend() {
// Check if the dump is already suspended
if (isSuspended) {
return isSuspended;
} else {
isSuspended = true;
return false;
}
}
/** Resume the dump, only if it was not already suspended.
* @param wasSuspended flag to tell if the dump was already suspended (true; false otherwise)
*/
public static void resume(final Boolean wasSuspended) {
if (!wasSuspended) {
isSuspended = false;
}
}
/** In case dump is suspended and an exception is thrown,
* allows the dump to end nicely.
*/
public static void endNicely() {
isSuspended = false;
if (isActive()) deactivate();
}
/** Check if dump is active for this thread.
* @return true if dump is active for this thread
*/
public static boolean isActive() {
return DUMP.get() != null;
return DUMP.get() != null && !isSuspended;
}
/** Dump DEM cell data.
......@@ -135,26 +169,25 @@ public class DumpManager {
/** Dump a direct location computation.
* @param date date of the location
* @param position pixel position in spacecraft frame
* @param sensorPosition sensor position in spacecraft frame
* @param los normalized line-of-sight in spacecraft frame
* @param lightTimeCorrection flag for light time correction
* @param aberrationOfLightCorrection flag for aberration of light correction
* @exception RuggedException if date cannot be converted to UTC
* @param refractionCorrection flag for refraction correction
*/
public static void dumpDirectLocation(final AbsoluteDate date, final Vector3D position, final Vector3D los,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection)
throws RuggedException {
public static void dumpDirectLocation(final AbsoluteDate date, final Vector3D sensorPosition, final Vector3D los,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection,
final boolean refractionCorrection) {
if (isActive()) {
DUMP.get().dumpDirectLocation(date, position, los, lightTimeCorrection, aberrationOfLightCorrection);
DUMP.get().dumpDirectLocation(date, sensorPosition, los, lightTimeCorrection, aberrationOfLightCorrection,
refractionCorrection);
}
}
/** 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);
}
......@@ -163,17 +196,22 @@ public class DumpManager {
/** Dump an inverse location computation.
* @param sensor sensor
* @param point point to localize
* @param ellipsoid the used ellipsoid
* @param minLine minimum line number
* @param maxLine maximum line number
* @param lightTimeCorrection flag for light time correction
* @param aberrationOfLightCorrection flag for aberration of light correction
* @param refractionCorrection flag for refraction correction
*/
public static void dumpInverseLocation(final LineSensor sensor, final GeodeticPoint point,
final ExtendedEllipsoid ellipsoid,
final int minLine, final int maxLine,
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection) {
final boolean lightTimeCorrection, final boolean aberrationOfLightCorrection,
final boolean refractionCorrection) {
if (isActive()) {
DUMP.get().dumpInverseLocation(sensor, point, minLine, maxLine,
lightTimeCorrection, aberrationOfLightCorrection);
lightTimeCorrection, aberrationOfLightCorrection, refractionCorrection);
DUMP.get().dumpEllipsoid(ellipsoid);
}
}
......@@ -191,11 +229,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);
}
......@@ -203,10 +239,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);
}
......@@ -217,10 +251,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);
}
......@@ -230,10 +262,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);
}
......
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -33,9 +33,10 @@ import java.util.List;
import java.util.Map;
import java.util.NavigableMap;
import java.util.TreeMap;
import java.util.regex.Pattern;
import java.util.stream.Stream;
import org.hipparchus.analysis.differentiation.DerivativeStructure;
import org.hipparchus.analysis.differentiation.Derivative;
import org.hipparchus.exception.LocalizedCoreFormats;
import org.hipparchus.geometry.euclidean.threed.FieldVector3D;
import org.hipparchus.geometry.euclidean.threed.Rotation;
......@@ -45,7 +46,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;
......@@ -61,7 +61,10 @@ import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.rugged.los.TimeDependentLOS;
import org.orekit.rugged.raster.TileUpdater;
import org.orekit.rugged.raster.UpdatableTile;
import org.orekit.rugged.utils.DSGenerator;
import org.orekit.rugged.refraction.AtmosphericRefraction;
import org.orekit.rugged.refraction.MultiLayerModel;
import org.orekit.rugged.utils.DerivativeGenerator;
import org.orekit.rugged.utils.ExtendedEllipsoid;
import org.orekit.rugged.utils.SpacecraftToObservedBody;
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScalesFactory;
......@@ -69,6 +72,7 @@ import org.orekit.utils.ParameterDriver;
/** Replayer for Rugged debug dumps.
* @author Luc Maisonobe
* @author Guylaine Prat
* @see DumpManager
* @see Dump
*/
......@@ -110,6 +114,9 @@ public class DumpReplayer {
/** Keyword for aberration of light correction fields. */
private static final String ABERRATION = "aberration";
/** Keyword for atmospheric refraction correction fields. */
private static final String REFRACTION = "refraction";
/** Keyword for min date fields. */
private static final String MIN_DATE = "minDate";
......@@ -215,6 +222,15 @@ public class DumpReplayer {
/** Keyword for target direction. */
private static final String TARGET_DIRECTION = "targetDirection";
/** Keyword for null result. */
private static final String NULL_RESULT = "NULL";
/** Pattern for delimiting regular expressions. */
private static final Pattern SEPARATOR = Pattern.compile("\\s+");
/** Empty pattern. */
private static final Pattern PATTERN = Pattern.compile(" ");
/** Constant elevation for constant elevation algorithm. */
private double constantElevation;
......@@ -257,22 +273,25 @@ public class DumpReplayer {
/** Flag for aberration of light correction. */
private boolean aberrationOfLightCorrection;
/** Flag for atmospheric refraction. */
private boolean atmosphericRefraction;
/** Dumped calls. */
private final List<DumpedCall> calls;
/** Simple constructor.
*/
public DumpReplayer() {
tiles = new ArrayList<ParsedTile>();
sensors = new ArrayList<ParsedSensor>();
calls = new ArrayList<DumpedCall>();
tiles = new ArrayList<>();
sensors = new ArrayList<>();
calls = new ArrayList<>();
}
/** 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"));
......@@ -288,9 +307,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();
......@@ -305,8 +323,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);
......@@ -316,19 +333,25 @@ public class DumpReplayer {
throw new RuggedException(RuggedMessages.NO_DEM_DATA,
FastMath.toDegrees(latitude), FastMath.toDegrees(longitude));
}
}, 8);
}
builder.setEllipsoid(ellipsoid);
builder.setLightTimeCorrection(lightTimeCorrection);
builder.setAberrationOfLightCorrection(aberrationOfLightCorrection);
if (atmosphericRefraction) { // Use the default model with the default configuration values
final ExtendedEllipsoid extendedEllipsoid = builder.getEllipsoid();
final AtmosphericRefraction atmosphericModel = new MultiLayerModel(extendedEllipsoid);
// Build Rugged with atmospheric refraction model
builder.setRefractionCorrection(atmosphericModel);
}
builder.setEllipsoid(ellipsoid);
// build missing transforms by extrapolating the parsed ones
final int n = (int) FastMath.ceil(maxDate.durationFrom(minDate) / tStep);
final List<Transform> b2iList = new ArrayList<Transform>(n);
final List<Transform> s2iList = new ArrayList<Transform>(n);
final List<Transform> b2iList = new ArrayList<>(n);
final List<Transform> s2iList = new ArrayList<>(n);
for (int i = 0; i < n; ++i) {
if (bodyToInertial.containsKey(i)) {
// the i-th transform was dumped
......@@ -362,7 +385,7 @@ public class DumpReplayer {
final ByteArrayInputStream bis = new ByteArrayInputStream(bos.toByteArray());
builder.setTrajectoryAndTimeSpan(bis);
final List<SensorMeanPlaneCrossing> planeCrossings = new ArrayList<SensorMeanPlaneCrossing>();
final List<SensorMeanPlaneCrossing> planeCrossings = new ArrayList<>();
for (final ParsedSensor parsedSensor : sensors) {
final LineSensor sensor = new LineSensor(parsedSensor.name,
parsedSensor,
......@@ -392,25 +415,10 @@ public class DumpReplayer {
return rugged;
} catch (IOException ioe) {
throw new RuggedException(ioe, LocalizedCoreFormats.SIMPLE_MESSAGE, ioe.getLocalizedMessage());
} catch (SecurityException e) {
// this should never happen
throw RuggedException.createInternalError(e);
} catch (NoSuchMethodException e) {
} catch (IOException | NoSuchMethodException | IllegalAccessException | InvocationTargetException e) {
// this should never happen
throw RuggedException.createInternalError(e);
} catch (IllegalArgumentException e) {
// this should never happen
throw RuggedException.createInternalError(e);
} catch (IllegalAccessException e) {
// this should never happen
throw RuggedException.createInternalError(e);
} catch (InvocationTargetException e) {
// this should never happen
throw RuggedException.createInternalError(e);
throw new RuggedInternalError(e);
}
}
/** Get a sensor by name.
......@@ -435,9 +443,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,
......@@ -488,8 +495,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);
......@@ -513,8 +519,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);
}
......@@ -523,8 +528,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);
}
......@@ -538,49 +541,49 @@ 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 {
if (fields.length < 14 ||
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(DATE) ||
!fields[2].equals(POSITION) || !fields[6].equals(LOS) ||
!fields[10].equals(LIGHT_TIME) || !fields[12].equals(ABERRATION)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
!fields[10].equals(LIGHT_TIME) || !fields[12].equals(ABERRATION) ||
!fields[14].equals(REFRACTION)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final AbsoluteDate date = new AbsoluteDate(fields[1], TimeScalesFactory.getUTC());
final Vector3D position = new Vector3D(Double.parseDouble(fields[3]),
Double.parseDouble(fields[4]),
Double.parseDouble(fields[5]));
final Vector3D los = new Vector3D(Double.parseDouble(fields[7]),
Double.parseDouble(fields[8]),
Double.parseDouble(fields[9]));
if (global.calls.isEmpty()) {
global.lightTimeCorrection = Boolean.parseBoolean(fields[11]);
global.aberrationOfLightCorrection = Boolean.parseBoolean(fields[13]);
global.atmosphericRefraction = Boolean.parseBoolean(fields[15]);
} else {
if (global.lightTimeCorrection != Boolean.parseBoolean(fields[11])) {
throw new RuggedException(RuggedMessages.LIGHT_TIME_CORRECTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
final AbsoluteDate date = new AbsoluteDate(fields[1], TimeScalesFactory.getUTC());
final Vector3D position = new Vector3D(Double.parseDouble(fields[3]),
Double.parseDouble(fields[4]),
Double.parseDouble(fields[5]));
final Vector3D los = new Vector3D(Double.parseDouble(fields[7]),
Double.parseDouble(fields[8]),
Double.parseDouble(fields[9]));
if (global.calls.isEmpty()) {
global.lightTimeCorrection = Boolean.parseBoolean(fields[11]);
global.aberrationOfLightCorrection = Boolean.parseBoolean(fields[13]);
} else {
if (global.lightTimeCorrection != Boolean.parseBoolean(fields[11])) {
throw new RuggedException(RuggedMessages.LIGHT_TIME_CORRECTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
if (global.aberrationOfLightCorrection != Boolean.parseBoolean(fields[13])) {
throw new RuggedException(RuggedMessages.ABERRATION_OF_LIGHT_CORRECTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
if (global.aberrationOfLightCorrection != Boolean.parseBoolean(fields[13])) {
throw new RuggedException(RuggedMessages.ABERRATION_OF_LIGHT_CORRECTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
global.calls.add(new DumpedCall() {
if (global.atmosphericRefraction != Boolean.parseBoolean(fields[15])) {
throw new RuggedException(RuggedMessages.ATMOSPHERIC_REFRACTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
}
global.calls.add(new DumpedCall() {
/** {@inheritDoc} */
@Override
public Object execute(final Rugged rugged) throws RuggedException {
return rugged.directLocation(date, position, los);
}
/** {@inheritDoc} */
@Override
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. */
......@@ -588,17 +591,25 @@ 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 {
if (fields.length < 6 || !fields[0].equals(LATITUDE) ||
!fields[2].equals(LONGITUDE) || !fields[4].equals(ELEVATION)) {
public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) {
if (fields.length == 1) {
if (fields[0].equals(NULL_RESULT)) {
final GeodeticPoint gp = null;
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = gp;
} else {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
} else 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);
} else {
final GeodeticPoint gp = new GeodeticPoint(Double.parseDouble(fields[1]),
Double.parseDouble(fields[3]),
Double.parseDouble(fields[5]));
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = gp;
}
final GeodeticPoint gp = new GeodeticPoint(Double.parseDouble(fields[1]),
Double.parseDouble(fields[3]),
Double.parseDouble(fields[5]));
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = gp;
}
},
......@@ -608,30 +619,24 @@ 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 {
if (fields.length < 10 ||
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)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
global.minDate = new AbsoluteDate(fields[1], TimeScalesFactory.getUTC());
global.maxDate = new AbsoluteDate(fields[3], TimeScalesFactory.getUTC());
global.tStep = Double.parseDouble(fields[5]);
global.tolerance = Double.parseDouble(fields[7]);
global.bodyToInertial = new TreeMap<Integer, Transform>();
global.scToInertial = new TreeMap<Integer, Transform>();
try {
global.inertialFrame = FramesFactory.getFrame(Predefined.valueOf(fields[9]));
} catch (IllegalArgumentException iae) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
} catch (OrekitException oe) {
throw new RuggedException(oe, oe.getSpecifier(), oe.getParts());
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
global.minDate = new AbsoluteDate(fields[1], TimeScalesFactory.getUTC());
global.maxDate = new AbsoluteDate(fields[3], TimeScalesFactory.getUTC());
global.tStep = Double.parseDouble(fields[5]);
global.tolerance = Double.parseDouble(fields[7]);
global.bodyToInertial = new TreeMap<Integer, Transform>();
global.scToInertial = new TreeMap<Integer, Transform>();
try {
global.inertialFrame = FramesFactory.getFrame(Predefined.valueOf(fields[9]));
} catch (IllegalArgumentException iae) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
}
},
/** Parser for observation transforms dump lines. */
......@@ -639,8 +644,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) ||
......@@ -698,8 +702,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)) {
......@@ -730,8 +733,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);
......@@ -758,13 +760,13 @@ 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 {
if (fields.length < 16 ||
public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) {
if (fields.length < 18 ||
!fields[0].equals(SENSOR_NAME) ||
!fields[2].equals(LATITUDE) || !fields[4].equals(LONGITUDE) || !fields[6].equals(ELEVATION) ||
!fields[8].equals(MIN_LINE) || !fields[10].equals(MAX_LINE) ||
!fields[12].equals(LIGHT_TIME) || !fields[14].equals(ABERRATION)) {
!fields[12].equals(LIGHT_TIME) || !fields[14].equals(ABERRATION) ||
!fields[16].equals(REFRACTION)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
......@@ -776,6 +778,7 @@ public class DumpReplayer {
if (global.calls.isEmpty()) {
global.lightTimeCorrection = Boolean.parseBoolean(fields[13]);
global.aberrationOfLightCorrection = Boolean.parseBoolean(fields[15]);
global.atmosphericRefraction = Boolean.parseBoolean(fields[17]);
} else {
if (global.lightTimeCorrection != Boolean.parseBoolean(fields[13])) {
throw new RuggedException(RuggedMessages.LIGHT_TIME_CORRECTION_REDEFINED,
......@@ -785,12 +788,16 @@ public class DumpReplayer {
throw new RuggedException(RuggedMessages.ABERRATION_OF_LIGHT_CORRECTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
if (global.atmosphericRefraction != Boolean.parseBoolean(fields[17])) {
throw new RuggedException(RuggedMessages.ATMOSPHERIC_REFRACTION_REDEFINED,
l, file.getAbsolutePath(), line);
}
}
global.calls.add(new DumpedCall() {
/** {@inheritDoc} */
@Override
public Object execute(final Rugged rugged) throws RuggedException {
public Object execute(final Rugged rugged) {
return rugged.inverseLocation(sensorName, point, minLine, maxLine);
}
......@@ -804,15 +811,23 @@ 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 {
if (fields.length < 4 || !fields[0].equals(LINE_NUMBER) || !fields[2].equals(PIXEL_NUMBER)) {
public void parse(final int l, final File file, final String line, final String[] fields, final DumpReplayer global) {
if (fields.length == 1) {
if (fields[0].equals(NULL_RESULT)) {
final SensorPixel sp = null;
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = sp;
} else {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
} else if (fields.length < 4 || !fields[0].equals(LINE_NUMBER) || !fields[2].equals(PIXEL_NUMBER)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
} else {
final SensorPixel sp = new SensorPixel(Double.parseDouble(fields[1]),
Double.parseDouble(fields[3]));
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = sp;
}
final SensorPixel sp = new SensorPixel(Double.parseDouble(fields[1]),
Double.parseDouble(fields[3]));
final DumpedCall last = global.calls.get(global.calls.size() - 1);
last.expected = sp;
}
},
......@@ -822,8 +837,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);
......@@ -842,53 +856,46 @@ 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 {
if (fields.length < 16 || !fields[0].equals(SENSOR_NAME) ||
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) ||
!fields[10].equals(NORMAL) || !fields[14].equals(CACHED_RESULTS)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
final int minLine = Integer.parseInt(fields[3]);
final int maxLine = Integer.parseInt(fields[5]);
final int maxEval = Integer.parseInt(fields[7]);
final double accuracy = Double.parseDouble(fields[9]);
final Vector3D normal = new Vector3D(Double.parseDouble(fields[11]),
Double.parseDouble(fields[12]),
Double.parseDouble(fields[13]));
final int n = Integer.parseInt(fields[15]);
final CrossingResult[] cachedResults = new CrossingResult[n];
int base = 16;
for (int i = 0; i < n; ++i) {
if (fields.length < base + 15 || !fields[base].equals(LINE_NUMBER) ||
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
final int minLine = Integer.parseInt(fields[3]);
final int maxLine = Integer.parseInt(fields[5]);
final int maxEval = Integer.parseInt(fields[7]);
final double accuracy = Double.parseDouble(fields[9]);
final Vector3D normal = new Vector3D(Double.parseDouble(fields[11]),
Double.parseDouble(fields[12]),
Double.parseDouble(fields[13]));
final int n = Integer.parseInt(fields[15]);
final CrossingResult[] cachedResults = new CrossingResult[n];
int base = 16;
for (int i = 0; i < n; ++i) {
if (fields.length < base + 15 || !fields[base].equals(LINE_NUMBER) ||
!fields[base + 2].equals(DATE) || !fields[base + 4].equals(TARGET) ||
!fields[base + 8].equals(TARGET_DIRECTION)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final double ln = Double.parseDouble(fields[base + 1]);
final AbsoluteDate date = new AbsoluteDate(fields[base + 3], TimeScalesFactory.getUTC());
final Vector3D target = new Vector3D(Double.parseDouble(fields[base + 5]),
Double.parseDouble(fields[base + 6]),
Double.parseDouble(fields[base + 7]));
final Vector3D targetDirection = new Vector3D(Double.parseDouble(fields[base + 9]),
Double.parseDouble(fields[base + 10]),
Double.parseDouble(fields[base + 11]));
final Vector3D targetDirectionDerivative = new Vector3D(Double.parseDouble(fields[base + 12]),
Double.parseDouble(fields[base + 13]),
Double.parseDouble(fields[base + 14]));
cachedResults[i] = new CrossingResult(date, ln, target, targetDirection, targetDirectionDerivative);
base += 15;
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
global.getSensor(sensorName).setMeanPlane(new ParsedMeanPlane(minLine, maxLine, maxEval, accuracy, normal, cachedResults));
} catch (OrekitException oe) {
throw new RuggedException(oe, oe.getSpecifier(), oe.getParts());
final double ln = Double.parseDouble(fields[base + 1]);
final AbsoluteDate date = new AbsoluteDate(fields[base + 3], TimeScalesFactory.getUTC());
final Vector3D target = new Vector3D(Double.parseDouble(fields[base + 5]),
Double.parseDouble(fields[base + 6]),
Double.parseDouble(fields[base + 7]));
final Vector3D targetDirection = new Vector3D(Double.parseDouble(fields[base + 9]),
Double.parseDouble(fields[base + 10]),
Double.parseDouble(fields[base + 11]));
final Vector3D targetDirectionDerivative = new Vector3D(Double.parseDouble(fields[base + 12]),
Double.parseDouble(fields[base + 13]),
Double.parseDouble(fields[base + 14]));
cachedResults[i] = new CrossingResult(date, ln, target, targetDirection, targetDirectionDerivative);
base += 15;
}
global.getSensor(sensorName).setMeanPlane(new ParsedMeanPlane(minLine, maxLine, maxEval, accuracy, normal, cachedResults));
}
},
/** Parser for sensor LOS dump lines. */
......@@ -896,27 +903,20 @@ 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 {
if (fields.length < 10 || !fields[0].equals(SENSOR_NAME) ||
!fields[2].equals(DATE) || !fields[4].equals(PIXEL_NUMBER) ||
!fields[6].equals(LOS)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
final AbsoluteDate date = new AbsoluteDate(fields[3], TimeScalesFactory.getUTC());
final int pixelNumber = Integer.parseInt(fields[5]);
final Vector3D los = new Vector3D(Double.parseDouble(fields[7]),
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());
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)) {
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
final AbsoluteDate date = new AbsoluteDate(fields[3], TimeScalesFactory.getUTC());
final int pixelNumber = Integer.parseInt(fields[5]);
final Vector3D los = new Vector3D(Double.parseDouble(fields[7]),
Double.parseDouble(fields[8]),
Double.parseDouble(fields[9]));
global.getSensor(sensorName).setLOS(date, pixelNumber, los);
}
},
/** Parser for sensor datation dump lines. */
......@@ -924,24 +924,16 @@ 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 {
if (fields.length < 6 || !fields[0].equals(SENSOR_NAME) ||
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);
}
final String sensorName = fields[1];
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());
throw new RuggedException(RuggedMessages.CANNOT_PARSE_LINE, l, file, line);
}
final String sensorName = fields[1];
final double lineNumber = Double.parseDouble(fields[3]);
final AbsoluteDate date = new AbsoluteDate(fields[5], TimeScalesFactory.getUTC());
global.getSensor(sensorName).setDatation(lineNumber, date);
}
},
/** Parser for sensor rate dump lines. */
......@@ -949,8 +941,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);
......@@ -969,10 +960,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)) {
......@@ -981,14 +970,14 @@ public class DumpReplayer {
final int colon = line.indexOf(':');
if (colon > 0) {
final String parsedKey = line.substring(0, colon).trim().replaceAll(" ", "_").toUpperCase();
final String parsedKey = PATTERN.matcher(line.substring(0, colon).trim()).replaceAll("_").toUpperCase();
try {
final LineParser parser = LineParser.valueOf(parsedKey);
final String[] fields;
if (colon + 1 >= line.length()) {
fields = new String[0];
} else {
fields = line.substring(colon + 1).trim().split("\\s+");
fields = SEPARATOR.split(line.substring(colon + 1).trim());
}
parser.parse(l, file, line, fields, global);
} catch (IllegalArgumentException iae) {
......@@ -1007,11 +996,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(final int l, final File file, final String line, final String[] fields,
final DumpReplayer global)
throws RuggedException;
public abstract void parse(int l, File file, String line, String[] fields, DumpReplayer global);
}
......@@ -1072,16 +1058,14 @@ public class DumpReplayer {
public boolean isInterpolable(final double latitude, final double longitude) {
final int latitudeIndex = (int) FastMath.floor((latitude - minLatitude) / latitudeStep);
final int longitudeIndex = (int) FastMath.floor((longitude - minLongitude) / longitudeStep);
return (latitudeIndex >= 0) && (latitudeIndex <= latitudeRows - 2) &&
(longitudeIndex >= 0) && (longitudeIndex <= longitudeColumns - 2);
return latitudeIndex >= 0 && latitudeIndex <= latitudeRows - 2 &&
longitudeIndex >= 0 && longitudeIndex <= longitudeColumns - 2;
}
/** 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,
......@@ -1189,7 +1173,7 @@ public class DumpReplayer {
public Vector3D getLOS(final int index, final AbsoluteDate date) {
final List<Pair<AbsoluteDate, Vector3D>> list = losMap.get(index);
if (list == null) {
throw RuggedException.createInternalError(null);
throw new RuggedInternalError(null);
}
if (list.size() < 2) {
......@@ -1217,12 +1201,12 @@ public class DumpReplayer {
/** {@inheritDoc} */
@Override
public FieldVector3D<DerivativeStructure> getLOSDerivatives(final int index, final AbsoluteDate date,
final DSGenerator generator) {
public <T extends Derivative<T>> FieldVector3D<T> getLOSDerivatives(final int index, final AbsoluteDate date,
final DerivativeGenerator<T> generator) {
final Vector3D los = getLOS(index, date);
return new FieldVector3D<DerivativeStructure>(generator.constant(los.getX()),
generator.constant(los.getY()),
generator.constant(los.getZ()));
return new FieldVector3D<>(generator.constant(los.getX()),
generator.constant(los.getY()),
generator.constant(los.getZ()));
}
/** Set a datation pair.
......@@ -1268,6 +1252,33 @@ public class DumpReplayer {
}
/** {@inheritDoc} */
@Override
public double getLine(final AbsoluteDate date) {
if (datation.size() < 2) {
return datation.get(0).getFirst();
}
// find entries bracketing the date
int sup = 0;
while (sup < datation.size() - 1) {
if (datation.get(sup).getSecond().compareTo(date) >= 0) {
break;
}
++sup;
}
final int inf = (sup == 0) ? sup++ : (sup - 1);
final double lInf = datation.get(inf).getFirst();
final AbsoluteDate dInf = datation.get(inf).getSecond();
final double lSup = datation.get(sup).getFirst();
final AbsoluteDate dSup = datation.get(sup).getSecond();
final double alpha = date.durationFrom(dInf) / dSup.durationFrom(dInf);
return alpha * lSup + (1 - alpha) * lInf;
}
/** Set a rate.
* @param lineNumber line number
* @param rate lines rate
......@@ -1370,9 +1381,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);
}
......
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -27,15 +27,15 @@ import org.hipparchus.exception.LocalizedException;
* the rugged library classes.
* <p>
* This class is heavily based on Orekit {@link org.orekit.errors.OrekitException},
* This class is heavily based on {@code OrekitException},
* which is distributed under the terms of the Apache License V2.
* </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;
......@@ -51,7 +51,7 @@ public class RuggedException extends Exception implements LocalizedException {
* @param specifier format specifier (to be translated)
* @param parts parts to insert in the format (no translation)
*/
public RuggedException(final Localizable specifier, final Object ... parts) {
public RuggedException(final Localizable specifier, final Object... parts) {
this.specifier = specifier;
this.parts = (parts == null) ? new Object[0] : parts.clone();
}
......@@ -63,7 +63,7 @@ public class RuggedException extends Exception implements LocalizedException {
* @param parts parts to insert in the format (no translation)
*/
public RuggedException(final Throwable cause, final Localizable specifier,
final Object ... parts) {
final Object... parts) {
super(cause);
this.specifier = specifier;
this.parts = (parts == null) ? new Object[0] : parts.clone();
......@@ -109,41 +109,8 @@ public class RuggedException extends Exception implements LocalizedException {
* @return a message string
*/
private static String buildMessage(final Locale locale, final Localizable specifier,
final Object ... parts) {
final Object... parts) {
return (specifier == null) ? "" : new MessageFormat(specifier.getLocalizedString(locale), locale).format(parts);
}
/** Create an {@link java.lang.RuntimeException} for an internal error.
* @param cause underlying cause
* @return an {@link java.lang.RuntimeException} for an internal error
*/
public static RuntimeException createInternalError(final Throwable cause) {
/** Format specifier (to be translated). */
final Localizable specifier = RuggedMessages.INTERNAL_ERROR;
/** Parts to insert in the format (no translation). */
final String parts = "rugged-developers@orekit.org";
return new RuntimeException() {
/** Serializable UID. */
private static final long serialVersionUID = 20140309L;
/** {@inheritDoc} */
@Override
public String getMessage() {
return buildMessage(Locale.US, specifier, parts);
}
/** {@inheritDoc} */
@Override
public String getLocalizedMessage() {
return buildMessage(Locale.getDefault(), specifier, parts);
}
};
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -22,11 +22,15 @@ package org.orekit.rugged.errors;
* this exception. Typical examples are propagation methods that are used inside Hipparchus
* optimizers, integrators or solvers.</p>
* <p>
* This class is heavily based on Orekit {@link org.orekit.errors.OrekitException},
* This class is heavily based on {@code OrekitException},
* which is distributed under the terms of the Apache License V2.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
* @deprecated as of 2.1, this class is not used anymore, as {@link RuggedException}
* is now an unchecked exception
*/
@Deprecated
public class RuggedExceptionWrapper extends RuntimeException {
/** serializable UID. */
......
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
* (the "License"); you may not use this file except in compliance with
* the License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
package org.orekit.rugged.errors;
import java.text.MessageFormat;
import java.util.Locale;
import org.hipparchus.exception.Localizable;
import org.hipparchus.exception.LocalizedException;
/** Extension of {@link java.lang.Runtime} with localized message for internal errors only.
* @since 2.1
*/
public class RuggedInternalError extends RuntimeException implements LocalizedException {
/** Serializable UID. */
private static final long serialVersionUID = 20190305L;
/** Format specifier (to be translated). */
private final Localizable specifier = RuggedMessages.INTERNAL_ERROR;
/** Parts to insert in the format (no translation). */
private final String[] parts = new String[] {
"https://gitlab.orekit.org/orekit/rugged/issues"
};
/** Create an exception with localized message.
* @param cause underlying cause
*/
public RuggedInternalError(final Throwable cause) {
super(cause);
}
/** {@inheritDoc} */
@Override
public String getMessage(final Locale locale) {
return buildMessage(locale);
}
/** {@inheritDoc} */
@Override
public String getMessage() {
return buildMessage(Locale.US);
}
/** {@inheritDoc} */
@Override
public String getLocalizedMessage() {
return buildMessage(Locale.getDefault());
}
/** {@inheritDoc} */
@Override
public Localizable getSpecifier() {
return specifier;
}
/** {@inheritDoc} */
@Override
public Object[] getParts() {
return parts.clone();
}
/**
* Builds a message string by from a pattern and its arguments.
* @param locale Locale in which the message should be translated
* @return a message string
*/
private String buildMessage(final Locale locale) {
return new MessageFormat(specifier.getLocalizedString(locale), locale).format(parts);
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -16,17 +16,19 @@
*/
package org.orekit.rugged.errors;
import org.hipparchus.exception.Localizable;
import java.io.IOException;
import java.io.InputStream;
import java.io.InputStreamReader;
import java.net.URL;
import java.net.URLConnection;
import java.nio.charset.StandardCharsets;
import java.util.Locale;
import java.util.MissingResourceException;
import java.util.PropertyResourceBundle;
import java.util.ResourceBundle;
import org.hipparchus.exception.Localizable;
/**
* Enumeration for localized messages formats.
......@@ -42,7 +44,7 @@ import java.util.ResourceBundle;
* translation is missing.
* </p>
* <p>
* This class is heavily based on Orekit {@link org.orekit.errors.OrekitMessages},
* This class is heavily based on {@code OrekitMessages},
* which is distributed under the terms of the Apache License V2.
* </p>
*/
......@@ -50,7 +52,7 @@ public enum RuggedMessages implements Localizable {
// CHECKSTYLE: stop JavadocVariable check
INTERNAL_ERROR("internal error, contact maintenance at {0}"),
INTERNAL_ERROR("internal error, please notify development team by creating an issue at {0}"),
OUT_OF_TILE_INDICES("no data at indices [{0}, {1}], tile only covers from [0, 0] to [{2}, {3}] (inclusive)"),
OUT_OF_TILE_ANGLES("no data at latitude {0} and longitude {1}, tile covers only latitudes {2} to {3} and longitudes {4} to {5}"),
NO_DEM_DATA("no Digital Elevation Model data at latitude {0} and longitude {1}"),
......@@ -66,18 +68,26 @@ public enum RuggedMessages implements Localizable {
DEM_ENTRY_POINT_IS_BEHIND_SPACECRAFT("line-of-sight enters the Digital Elevation Model behind spacecraft!"),
FRAMES_MISMATCH_WITH_INTERPOLATOR_DUMP("frame {0} does not match frame {1} from interpolator dump"),
NOT_INTERPOLATOR_DUMP_DATA("data is not an interpolator dump"),
ESTIMATED_PARAMETERS_NUMBER_MISMATCH("number of estimated parameters mismatch, expected {0} got {1}"),
DEBUG_DUMP_ALREADY_ACTIVE("debug dump is already active for this thread"),
DEBUG_DUMP_ACTIVATION_ERROR("unable to active debug dump with file {0}: {1}"),
DEBUG_DUMP_NOT_ACTIVE("debug dump is not active for this thread"),
CANNOT_PARSE_LINE("cannot parse line {0}, file {1}: {2}"),
LIGHT_TIME_CORRECTION_REDEFINED("light time correction redefined, line {0}, file {1}: {2}"),
ABERRATION_OF_LIGHT_CORRECTION_REDEFINED("aberration of light correction redefined, line {0}, file {1}: {2}"),
ATMOSPHERIC_REFRACTION_REDEFINED("atmospheric refraction correction redefined, line {0}, file {1}: {2}"),
TILE_ALREADY_DEFINED("tile {0} already defined, line {1}, file {2}: {3}"),
UNKNOWN_TILE("unknown tile {0}, line {1}, file {2}: {3}"),
NO_PARAMETERS_SELECTED("no parameters have been selected for estimation"),
NO_REFERENCE_MAPPINGS("no reference mappings for parameters estimation"),
DUPLICATED_PARAMETER_NAME("a different parameter with name {0} already exists");
DUPLICATED_PARAMETER_NAME("a different parameter with name {0} already exists"),
INVALID_RUGGED_NAME("invalid rugged name"),
UNSUPPORTED_REFINING_CONTEXT("refining using {0} rugged instance is not handled"),
NO_LAYER_DATA("no atmospheric layer data at altitude {0} (lowest altitude: {1})"),
INVALID_STEP("step {0} is not valid : {1}"),
INVALID_RANGE_FOR_LINES("range between min line {0} and max line {1} is invalid {2}"),
SENSOR_PIXEL_NOT_FOUND_IN_RANGE_LINES("impossible to find sensor pixel in given range lines (with atmospheric refraction) between lines {0} and {1}"),
SENSOR_PIXEL_NOT_FOUND_IN_PIXELS_LINE("impossible to find sensor pixel: pixel {0} outside interval [ {1} , {2} [ (with atmospheric refraction margin = {3})");
// CHECKSTYLE: resume JavadocVariable check
......@@ -96,20 +106,21 @@ public enum RuggedMessages implements Localizable {
}
/** {@inheritDoc} */
@Override
public String getSourceString() {
return sourceFormat;
}
/** {@inheritDoc} */
@Override
public String getLocalizedString(final Locale locale) {
try {
final ResourceBundle bundle =
ResourceBundle.getBundle(RESOURCE_BASE_NAME, locale, new UTF8Control());
if (bundle.getLocale().getLanguage().equals(locale.getLanguage())) {
final String translated = bundle.getString(name());
if ((translated != null) &&
(translated.length() > 0) &&
(!translated.toLowerCase().contains("missing translation"))) {
if (translated.length() > 0 &&
!translated.toLowerCase(locale).contains("missing translation")) {
// the value of the resource is the translated format
return translated;
}
......@@ -137,8 +148,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");
......@@ -157,11 +167,9 @@ public enum RuggedMessages implements Localizable {
stream = loader.getResourceAsStream(resourceName);
}
if (stream != null) {
try {
try (InputStreamReader inputStreamReader = new InputStreamReader(stream, StandardCharsets.UTF_8)) {
// Only this line is changed to make it to read properties files as UTF-8.
bundle = new PropertyResourceBundle(new InputStreamReader(stream, "UTF-8"));
} finally {
stream.close();
bundle = new PropertyResourceBundle(inputStreamReader);
}
}
return bundle;
......
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
* (the "License"); you may not use this file except in compliance with
* the License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
/**
*
* This package provides classes to generate and handle exceptions.
*
* @author Luc Maisonobe
* @author Guylaine Prat
*
*/
package org.orekit.rugged.errors;
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -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;
......@@ -41,6 +39,7 @@ import org.orekit.rugged.utils.NormalizedGeodeticPoint;
* corner points. It is not designed for operational use.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class BasicScanAlgorithm implements IntersectionAlgorithm {
......@@ -53,155 +52,153 @@ public class BasicScanAlgorithm implements IntersectionAlgorithm {
/** Maximum altitude encountered. */
private double hMax;
/** Algorithm Id.
* @since 2.2 */
private final AlgorithmId algorithmId;
/** Simple constructor.
* @param updater updater used to load Digital Elevation Model tiles
* @param maxCachedTiles maximum number of tiles stored in the cache
*/
public BasicScanAlgorithm(final TileUpdater updater, final int maxCachedTiles) {
cache = new TilesCache<SimpleTile>(new SimpleTileFactory(), updater, maxCachedTiles);
hMin = Double.POSITIVE_INFINITY;
hMax = Double.NEGATIVE_INFINITY;
this.cache = new TilesCache<>(new SimpleTileFactory(), updater, maxCachedTiles);
this.hMin = Double.POSITIVE_INFINITY;
this.hMax = Double.NEGATIVE_INFINITY;
this.algorithmId = AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY;
}
/** {@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(this.algorithmId);
// 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<>();
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(this.algorithmId);
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 {
DumpManager.dumpAlgorithm(AlgorithmId.BASIC_SLOW_EXHAUSTIVE_SCAN_FOR_TESTS_ONLY);
public double getElevation(final double latitude, final double longitude) {
DumpManager.dumpAlgorithm(this.algorithmId);
final Tile tile = cache.getTile(latitude, longitude);
return tile.interpolateElevation(latitude, longitude);
}
/** {@inheritDoc} */
@Override
public AlgorithmId getAlgorithmId() {
return this.algorithmId;
}
/** Check the overall min and max altitudes.
* @param tiles tiles to check
* @return true if the tile changed either min or max altitude
......@@ -267,5 +264,4 @@ public class BasicScanAlgorithm implements IntersectionAlgorithm {
final int rawIndex = tile.getFloorLongitudeIndex(longitude);
return FastMath.min(FastMath.max(0, rawIndex), tile.getLongitudeColumns());
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -18,61 +18,55 @@ 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;
/** Intersection ignoring Digital Elevation Model.
* <p>
* This dummy implementation simply uses the ellipsoid itself.
* This implementation uses a constant elevation over the ellipsoid.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class ConstantElevationAlgorithm implements IntersectionAlgorithm {
/** Constant elevation over ellipsoid. */
private final double constantElevation;
/** Algorithm Id.
* @since 2.2 */
private final AlgorithmId algorithmId;
/** Simple constructor.
* @param constantElevation constant elevation over ellipsoid
*/
public ConstantElevationAlgorithm(final double constantElevation) {
this.constantElevation = constantElevation;
this.algorithmId = AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID;
}
/** {@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(this.algorithmId, 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(this.algorithmId, 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}
......@@ -83,8 +77,13 @@ public class ConstantElevationAlgorithm implements IntersectionAlgorithm {
*/
@Override
public double getElevation(final double latitude, final double longitude) {
DumpManager.dumpAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID, constantElevation);
DumpManager.dumpAlgorithm(this.algorithmId, constantElevation);
return constantElevation;
}
/** {@inheritDoc} */
@Override
public AlgorithmId getAlgorithmId() {
return this.algorithmId;
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -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;
......@@ -28,20 +27,25 @@ import org.orekit.rugged.utils.NormalizedGeodeticPoint;
* This dummy implementation simply uses the ellipsoid itself.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class IgnoreDEMAlgorithm implements IntersectionAlgorithm {
/** Algorithm Id.
* @since 2.2 */
private final AlgorithmId algorithmId;
/** Simple constructor.
*/
public IgnoreDEMAlgorithm() {
this.algorithmId = AlgorithmId.IGNORE_DEM_USE_ELLIPSOID;
}
/** {@inheritDoc} */
@Override
public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los)
throws RuggedException {
DumpManager.dumpAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
final Vector3D position, final Vector3D los) {
DumpManager.dumpAlgorithm(this.algorithmId);
return ellipsoid.pointOnGround(position, los, 0.0);
}
......@@ -49,9 +53,8 @@ public class IgnoreDEMAlgorithm implements IntersectionAlgorithm {
@Override
public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los,
final NormalizedGeodeticPoint closeGuess)
throws RuggedException {
DumpManager.dumpAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
final NormalizedGeodeticPoint closeGuess) {
DumpManager.dumpAlgorithm(this.algorithmId);
return intersection(ellipsoid, position, los);
}
......@@ -63,8 +66,13 @@ public class IgnoreDEMAlgorithm implements IntersectionAlgorithm {
*/
@Override
public double getElevation(final double latitude, final double longitude) {
DumpManager.dumpAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
DumpManager.dumpAlgorithm(this.algorithmId);
return 0.0;
}
/** {@inheritDoc} */
@Override
public AlgorithmId getAlgorithmId() {
return this.algorithmId;
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -17,12 +17,13 @@
package org.orekit.rugged.intersection;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.api.AlgorithmId;
import org.orekit.rugged.utils.ExtendedEllipsoid;
import org.orekit.rugged.utils.NormalizedGeodeticPoint;
/** Interface for Digital Elevation Model intersection algorithm.
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public interface IntersectionAlgorithm {
......@@ -31,16 +32,14 @@ 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>
* This method is used to refine an intersection when a close guess is
* already known. The intersection is typically looked for by a direct
* {@link org.orekit.rugged.raster.Tile#cellIntersection(GeodeticPoint,
* {@link org.orekit.rugged.raster.Tile#cellIntersection(NormalizedGeodeticPoint,
* Vector3D, int, int) cell intersection} in the tile which already
* contains the close guess, or any similar very fast algorithm.
* </p>
......@@ -49,19 +48,20 @@ 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);
/** Get the algorithmId.
* @return the algorithmId
* @since 2.2
*/
AlgorithmId getAlgorithmId();
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -19,10 +19,10 @@ 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;
import org.orekit.rugged.errors.RuggedInternalError;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.intersection.IntersectionAlgorithm;
import org.orekit.rugged.raster.Tile;
......@@ -38,18 +38,30 @@ import org.orekit.rugged.utils.NormalizedGeodeticPoint;
* An Implicit Min/Max KD-Tree for Doing Efficient Terrain Line of Sight Calculations</a>.
* </p>
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class DuvenhageAlgorithm implements IntersectionAlgorithm {
/** Step size when skipping from one tile to a neighbor one, in meters. */
private static final double STEP = 0.01;
/** Maximum number of attempts to refine intersection.
* <p>
* This parameter is intended to prevent infinite loops.
* </p>
* @since 2.1 */
private static final int MAX_REFINING_ATTEMPTS = 100;
/** Cache for DEM tiles. */
private final TilesCache<MinMaxTreeTile> cache;
/** Flag for flat-body hypothesis. */
private final boolean flatBody;
/** Algorithm Id.
* @since 2.2 */
private final AlgorithmId algorithmId;
/** Simple constructor.
* @param updater updater used to load Digital Elevation Model tiles
* @param maxCachedTiles maximum number of tiles stored in the cache
......@@ -62,161 +74,230 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
*/
public DuvenhageAlgorithm(final TileUpdater updater, final int maxCachedTiles,
final boolean flatBody) {
this.cache = new TilesCache<MinMaxTreeTile>(new MinMaxTreeTileFactory(), updater, maxCachedTiles);
this.cache = new TilesCache<>(new MinMaxTreeTileFactory(), updater, maxCachedTiles);
this.flatBody = flatBody;
this.algorithmId = flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE;
}
/** {@inheritDoc} */
@Override
public NormalizedGeodeticPoint intersection(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los)
throws RuggedException {
try {
final Vector3D position, final Vector3D los) {
DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE);
DumpManager.dumpAlgorithm(this.algorithmId);
// compute intersection with ellipsoid
final NormalizedGeodeticPoint gp0 = ellipsoid.pointOnGround(position, los, 0.0);
// 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());
// locate the entry tile along the line-of-sight
MinMaxTreeTile tile = cache.getTile(gp0.getLatitude(), gp0.getLongitude());
NormalizedGeodeticPoint current = null;
double hMax = tile.getMaxElevation();
while (current == null) {
NormalizedGeodeticPoint current = null;
double hMax = tile.getMaxElevation();
while (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);
// 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!
// let's see if at least we are above DEM
try {
final NormalizedGeodeticPoint positionGP =
ellipsoid.transform(position, ellipsoid.getBodyFrame(), null, tile.getMinimumLongitude());
final double elevationAtPosition = tile.interpolateElevation(positionGP.getLatitude(), positionGP.getLongitude());
if (positionGP.getAltitude() >= elevationAtPosition) {
// we can use the current position as the entry point
current = positionGP;
} else {
current = null;
}
} catch (RuggedException re) {
if (re.getSpecifier() == RuggedMessages.OUT_OF_TILE_ANGLES) {
current = null;
}
}
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;
if (current == null) {
throw new RuggedException(RuggedMessages.DEM_ENTRY_POINT_IS_BEHIND_SPACECRAFT);
}
} else {
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
} else {
throw new RuggedInternalError(null);
}
}
}
}
// 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());
/** {@inheritDoc} */
@Override
public NormalizedGeodeticPoint refineIntersection(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los,
final NormalizedGeodeticPoint closeGuess) {
DumpManager.dumpAlgorithm(this.algorithmId);
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()));
if (tile.interpolateElevation(current.getLatitude(), current.getLongitude()) >= current.getAltitude()) {
} else {
// regular curved ellipsoid model
NormalizedGeodeticPoint currentGuess = closeGuess;
// normally, we should succeed at first attempt but in very rare cases
// we may loose the intersection (typically because some corrections introduced
// between the first intersection and the refining have slightly changed the
// relative geometry between Digital Elevation Model and Line Of Sight).
// In these rare cases, we have to recover a new intersection
for (int i = 0; i < MAX_REFINING_ATTEMPTS; ++i) {
final Vector3D delta = ellipsoid.transform(currentGuess).subtract(position);
final double s = Vector3D.dotProduct(delta, los) / los.getNormSq();
final Vector3D projectedP = new Vector3D(1, position, s, los);
final GeodeticPoint projected = ellipsoid.transform(projectedP, ellipsoid.getBodyFrame(), null);
final NormalizedGeodeticPoint normalizedProjected =
new NormalizedGeodeticPoint(projected.getLatitude(),
projected.getLongitude(),
projected.getAltitude(),
currentGuess.getLongitude());
final Tile tile = cache.getTile(normalizedProjected.getLatitude(), normalizedProjected.getLongitude());
final Vector3D topoLOS = ellipsoid.convertLos(normalizedProjected, los);
final int iLat = tile.getFloorLatitudeIndex(normalizedProjected.getLatitude());
final int iLon = tile.getFloorLongitudeIndex(normalizedProjected.getLongitude());
final NormalizedGeodeticPoint foundIntersection = tile.cellIntersection(normalizedProjected, topoLOS, iLat, iLon);
if (foundIntersection != null) {
// nominal case, we were able to refine the intersection
return foundIntersection;
} else {
// extremely rare case: we have lost the intersection
// find a start point for new search, leaving the current cell behind
final double cellBoundaryLatitude = tile.getLatitudeAtIndex(topoLOS.getY() <= 0 ? iLat : iLat + 1);
final double cellBoundaryLongitude = tile.getLongitudeAtIndex(topoLOS.getX() <= 0 ? iLon : iLon + 1);
final Vector3D cellExit = new Vector3D(1, selectClosest(latitudeCrossing(ellipsoid, projectedP, los, cellBoundaryLatitude, projectedP),
longitudeCrossing(ellipsoid, projectedP, los, cellBoundaryLongitude, projectedP),
projectedP),
STEP, los);
final GeodeticPoint egp = ellipsoid.transform(cellExit, ellipsoid.getBodyFrame(), null);
final NormalizedGeodeticPoint cellExitGP = new NormalizedGeodeticPoint(egp.getLatitude(),
egp.getLongitude(),
egp.getAltitude(),
currentGuess.getLongitude());
if (tile.interpolateElevation(cellExitGP.getLatitude(), cellExitGP.getLongitude()) >= cellExitGP.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
// during the very short forward step we used to move to next cell
// we consider this point to be OK
return current;
return cellExitGP;
}
} 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);
}
// We recompute fully a new guess, starting from the point after current cell
final GeodeticPoint currentGuessGP = intersection(ellipsoid, cellExit, los);
currentGuess = new NormalizedGeodeticPoint(currentGuessGP.getLatitude(),
currentGuessGP.getLongitude(),
currentGuessGP.getAltitude(),
projected.getLongitude());
}
}
// no intersection found
return null;
} // end test on flatbody
} 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 {
public double getElevation(final double latitude, final double longitude) {
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(this.algorithmId);
final Tile tile = cache.getTile(latitude, longitude);
return tile.interpolateElevation(latitude, longitude);
}
/** {@inheritDoc} */
@Override
public double getElevation(final double latitude, final double longitude)
throws RuggedException {
DumpManager.dumpAlgorithm(flatBody ? AlgorithmId.DUVENHAGE_FLAT_BODY : AlgorithmId.DUVENHAGE);
final Tile tile = cache.getTile(latitude, longitude);
return tile.interpolateElevation(latitude, longitude);
public AlgorithmId getAlgorithmId() {
return this.algorithmId;
}
/** Compute intersection of line with Digital Elevation Model in a sub-tile.
......@@ -233,19 +314,16 @@ 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
throw RuggedException.createInternalError(null);
throw new RuggedInternalError(null);
}
if (searchDomainSize(entryLat, entryLon, exitLat, exitLon) < 4) {
......@@ -287,7 +365,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;
}
......@@ -357,7 +435,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;
}
......@@ -439,16 +517,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;
......@@ -458,24 +533,26 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
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;
final Vector3D delta = ellipsoid.transform(gp).subtract(position);
final double s = Vector3D.dotProduct(delta, los) / los.getNormSq();
if (s > 0) {
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;
}
}
}
......@@ -515,12 +592,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();
......@@ -528,53 +602,52 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
final NormalizedGeodeticPoint exitGP = ellipsoid.transform(exitP, ellipsoid.getBodyFrame(), null, reference);
switch (tile.getLocation(exitGP.getLatitude(), exitGP.getLongitude())) {
case SOUTH_WEST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
position),
true);
case WEST :
return new LimitPoint(ellipsoid, reference,
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
true);
case NORTH_WEST:
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
position),
true);
case NORTH :
return new LimitPoint(ellipsoid, reference,
latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
true);
case NORTH_EAST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
position),
true);
case EAST :
return new LimitPoint(ellipsoid, reference,
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
true);
case SOUTH_EAST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
position),
true);
case SOUTH :
return new LimitPoint(ellipsoid, reference,
latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
true);
case HAS_INTERPOLATION_NEIGHBORS :
return new LimitPoint(exitGP, false);
default :
// this should never happen
throw RuggedException.createInternalError(null);
case SOUTH_WEST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
position),
true);
case WEST :
return new LimitPoint(ellipsoid, reference,
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
true);
case NORTH_WEST:
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMinimumLongitude(), exitP),
position),
true);
case NORTH :
return new LimitPoint(ellipsoid, reference,
latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
true);
case NORTH_EAST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMaximumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
position),
true);
case EAST :
return new LimitPoint(ellipsoid, reference,
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
true);
case SOUTH_EAST :
return new LimitPoint(ellipsoid, reference,
selectClosest(latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
longitudeCrossing(ellipsoid, position, los, tile.getMaximumLongitude(), exitP),
position),
true);
case SOUTH :
return new LimitPoint(ellipsoid, reference,
latitudeCrossing(ellipsoid, position, los, tile.getMinimumLatitude(), exitP),
true);
case HAS_INTERPOLATION_NEIGHBORS :
return new LimitPoint(exitGP, false);
default :
// this should never happen
throw new RuggedInternalError(null);
}
}
......@@ -596,7 +669,7 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
* @param latitude latitude with respect to ellipsoid
* @param closeReference reference point used to select the closest solution
* when there are two points at the desired latitude along the line
* @return point at altitude, or closeReference if no such point can be found
* @return point at latitude, or closeReference if no such point can be found
*/
private Vector3D latitudeCrossing(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los,
......@@ -614,8 +687,8 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
* @param los pixel line-of-sight, not necessarily normalized (in body frame)
* @param longitude longitude with respect to ellipsoid
* @param closeReference reference point used to select the closest solution
* when there are two points at the desired latitude along the line
* @return point at altitude, or closeReference if no such point can be found
* when there are two points at the desired longitude along the line
* @return point at longitude, or closeReference if no such point can be found
*/
private Vector3D longitudeCrossing(final ExtendedEllipsoid ellipsoid,
final Vector3D position, final Vector3D los,
......@@ -643,11 +716,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);
}
......@@ -677,5 +748,4 @@ public class DuvenhageAlgorithm implements IntersectionAlgorithm {
}
}
}
/* Copyright 2013-2016 CS Systèmes d'Information
* Licensed to CS Systèmes d'Information (CS) under one or more
/* Copyright 2013-2022 CS GROUP
* Licensed to CS GROUP (CS) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership.
* CS licenses this file to You under the Apache License, Version 2.0
......@@ -53,9 +53,9 @@ import org.orekit.rugged.utils.Selector;
* If we consider for example a tall 107 ⨉ 19 raw tile, the min/max kd-tree will
* have 9 levels:
* </p>
* <p>
* <table border="0">
* <tr BGCOLOR="#EEEEFF">
*
* <table summary="" border="0">
* <tr style="background-color:#EEEEFF;">
* <td>Level</td> <td>Number of sub-tiles</td> <td>Regular sub-tiles dimension</td></tr>
* <tr> <td align="center">8</td> <td align="center">107 ⨉ 10</td> <td align="center"> 1 ⨉ 2</td>
* <tr> <td align="center">7</td> <td align="center"> 54 ⨉ 10</td> <td align="center"> 2 ⨉ 2</td>
......@@ -67,8 +67,7 @@ import org.orekit.rugged.utils.Selector;
* <tr> <td align="center">1</td> <td align="center"> 7 ⨉ 2</td> <td align="center">16 ⨉ 16</td>
* <tr> <td align="center">0</td> <td align="center"> 7 ⨉ 1</td> <td align="center">16 ⨉ 32</td>
* </table>
* </p>
* <p>
* @see MinMaxTreeTileFactory
* @author Luc Maisonobe
*/
......@@ -140,10 +139,10 @@ public class MinMaxTreeTile extends SimpleTile {
* considering also Eastwards and Northwards neighbors, and extends
* up to the center of these neighbors. As an example, lets consider
* four neighboring cells in some Digital Elevation Model:
* <table border="0" cellpadding="5" bgcolor="#f5f5dc">
* <tr><th bgcolor="#c9d5c9">j+1</th><td>11</td><td>10</td></tr>
* <tr><th bgcolor="#c9d5c9">j</th><td>12</td><td>11</td></tr>
* <tr bgcolor="#c9d5c9"><th>j/i</th><th>i</th><th>i+1</th></tr>
* <table summary="" border="0" cellpadding="5" style="background-color:#f5f5dc;">
* <tr><th style="background-color:#c9d5c9;">j+1</th><td>11</td><td>10</td></tr>
* <tr><th style="background-color:#c9d5c9;">j</th><td>12</td><td>11</td></tr>
* <tr style="background-color:#c9d5c9;"><th>j/i</th><th>i</th><th>i+1</th></tr>
* </table>
* When we interpolate elevation at a point located slightly South-West
* to the center of the (i+1, j+1) cell, we use all four cells in the
......@@ -154,7 +153,7 @@ public class MinMaxTreeTile extends SimpleTile {
* tree level l includes cell (i,j) but not cell (i+1, j+1). In other words,
* interpolation implies sub-tile boundaries are overshoot by one column to
* the East and one row to the North when computing min.
* </p>
*
* @param i row index of the cell
* @param j column index of the cell
* @param level tree level
......@@ -200,10 +199,10 @@ public class MinMaxTreeTile extends SimpleTile {
* considering also Eastwards and Northwards neighbors, and extends
* up to the center of these neighbors. As an example, lets consider
* four neighboring cells in some Digital Elevation Model:
* <table border="0" cellpadding="5" bgcolor="#f5f5dc">
* <tr><th bgcolor="#c9d5c9">j+1</th><td>11</td><td>12</td></tr>
* <tr><th bgcolor="#c9d5c9">j</th><td>10</td><td>11</td></tr>
* <tr bgcolor="#c9d5c9"><th>j/i</th><th>i</th><th>i+1</th></tr>
* <table summary="" border="0" cellpadding="5" style="background-color:#f5f5dc;">
* <tr><th style="background-color:#c9d5c9;">j+1</th><td>11</td><td>12</td></tr>
* <tr><th style="background-color:#c9d5c9;">j</th><td>10</td><td>11</td></tr>
* <tr style="background-color:#c9d5c9;"><th>j/i</th><th>i</th><th>i+1</th></tr>
* </table>
* When we interpolate elevation at a point located slightly South-West
* to the center of the (i+1, j+1) cell, we use all four cells in the
......@@ -214,7 +213,7 @@ public class MinMaxTreeTile extends SimpleTile {
* tree level l includes cell (i,j) but not cell (i+1, j+1). In other words,
* interpolation implies sub-tile boundaries are overshoot by one column to
* the East and one row to the North when computing max.
* </p>
*
* @param i row index of the cell
* @param j column index of the cell
* @param level tree level
......