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 3908 additions and 496 deletions
src/site/resources/images/rugged-logo.png

32.3 KiB

function DirectLocation()
clear all
%Put 'orekit-data.zip' in the current directory, if not I get an error in line 55 %org.orekit.errors.OrekitException: aucune donne d'historique UTC-TAI n'a t charge
% These seems to work if pasted to prompt.
% javaaddpath 'C:\ ... enter your path here ...\MATLAB'
% javaaddpath 'C:\.. enter your path here ...\MATLAB\orekit-7.1.jar'
% javaaddpath 'C:\.. enter your path here ...\\MATLAB\rugged-1.0.jar'
% javaaddpath 'C:\.. enter your path here... \\MATLAB\commons-math3-3.6.1.jar'
%%
import java.util.ArrayList;
import java.util.List;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.rugged.los.*;
import org.orekit.rugged.utils.*;
%% Configure Orekit. The file orekit-data.zip must be in current dir
import org.orekit.data.ZipJarCrawler
import org.orekit.time.AbsoluteDate
import org.orekit.time.TimeScalesFactory
DM=org.orekit.data.DataProvidersManager.getInstance();
crawler=org.orekit.data.ZipJarCrawler('orekit-data.zip');
DM.clearProviders();
DM.addProvider(crawler);
%%
%The raw viewing direction of pixel i with respect to the instrument is defined by the vector:
rawDirs = ArrayList();
for i =1:2000
%20 field of view, 2000 pixels
rawDirs.add (Vector3D(0,i*deg2rad(20)/2000,1));
end
%The instrument is oriented 10 off nadir around the X-axis, we need to rotate the viewing
%direction to obtain the line of sight in the satellite frame
losBuilder = LOSBuilder(rawDirs);
losBuilder.addTransform(FixedRotation(ParameterType.FIXED, Vector3D.PLUS_I, deg2rad(10)));
lineOfSight = losBuilder.build();
%%
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScalesFactory;
import org.orekit.rugged.linesensor.LinearLineDatation;
%We use Orekit for handling time and dates, and Rugged for defining the datation model:
utc = TimeScalesFactory.getUTC();
absDate = AbsoluteDate('2009-12-11T16:59:30.0', utc);
lineDatation = LinearLineDatation(absDate, 1, 20);
%%
import org.orekit.rugged.linesensor.LineSensor;
%With the LOS and the datation now defined , we can initialize a line sensor object in Rugged:
lineSensor = LineSensor('mySensor', lineDatation, Vector3D.ZERO, lineOfSight);
%%
import org.orekit.frames.*;
import org.orekit.utils.*;
%In our application, we simply need to know the name of the frames we are working with. Positions and
%velocities are given in the ITRF terrestrial frame, while the quaternions are given in EME2000
%inertial frame.
eme2000 = FramesFactory.getEME2000();
simpleEOP = true; % we don't want to compute tiny tidal effects at millimeter level
itrf = FramesFactory.getITRF(IERSConventions.IERS_2010, simpleEOP);
%%
satelliteQList = ArrayList();
gps=TimeScalesFactory.getGPS();
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:58:42.592937', -0.340236, 0.333952, -0.844012, -0.245684);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:06.592937', -0.354773, 0.329336, -0.837871, -0.252281);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:30.592937', -0.369237, 0.324612, -0.831445, -0.258824);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:54.592937', -0.3836, 0.319792, -0.824743, -0.265299);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:00:18.592937', -0.397834, 0.314883, -0.817777, -0.271695);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:00:42.592937', -0.411912, 0.309895, -0.810561, -0.278001);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:06.592937', -0.42581, 0.304838, -0.803111, -0.284206);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:30.592937', -0.439505, 0.299722, -0.795442, -0.290301);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:54.592937', -0.452976, 0.294556, -0.787571, -0.296279);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:02:18.592937', -0.466207, 0.28935, -0.779516, -0.302131);
%%
satellitePVList = ArrayList();
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:58:42.592937', -726361.466, -5411878.485, 4637549.599, -2463.635, -4447.634, -5576.736);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:04.192937', -779538.267, -5506500.533, 4515934.894, -2459.848, -4312.676, -5683.906);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:25.792937', -832615.368, -5598184.195, 4392036.13, -2454.395, -4175.564, -5788.201);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:47.392937', -885556.748, -5686883.696, 4265915.971, -2447.273, -4036.368, -5889.568);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:08.992937', -938326.32, -5772554.875, 4137638.207, -2438.478, -3895.166, -5987.957);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:30.592937', -990887.942, -5855155.21, 4007267.717, -2428.011, -3752.034, -6083.317);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:52.192937', -1043205.448, -5934643.836, 3874870.441, -2415.868, -3607.05, -6175.6);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:13.792937', -1095242.669, -6010981.571, 3740513.34, -2402.051, -3460.291, -6264.76);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:35.392937', -1146963.457, -6084130.93, 3604264.372, -2386.561, -3311.835, -6350.751);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:56.992937', -1198331.706, -6154056.146, 3466192.446, -2369.401, -3161.764, -6433.531);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:02:18.592937', -1249311.381, -6220723.191, 3326367.397, -2350.574, -3010.159, -6513.056);
%%
% import org.orekit.rugged.api.AlgorithmId;
% import org.orekit.rugged.api.BodyRotatingFrameId;
% import org.orekit.rugged.api.EllipsoidId;
% import org.orekit.rugged.api.InertialFrameId;
% import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.api.*;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.utils.*;
% import org.orekit.utils.CartesianDerivativesFilter;
rugged=RuggedBuilder();
rugged.setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
rugged.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
rugged.setTimeSpan(absDate, absDate.shiftedBy(60.0), 0.01, 5 / lineSensor.getRate(0));
rugged.setTrajectory(InertialFrameId.EME2000,...
satellitePVList, 4, CartesianDerivativesFilter.USE_P,...
satelliteQList, 4, AngularDerivativesFilter.USE_R);
rugged.addLineSensor(lineSensor);
Rugged=rugged.build();
%%
import org.orekit.bodies.GeodeticPoint;
position = lineSensor.getPosition(); % This returns a zero vector since we set the relative position of the sensor w.r.T the satellite to 0.
firstLineDate = lineSensor.getDate(0);
los = lineSensor.getLos(firstLineDate, 0);
upLeftPoint = Rugged.directLocation(firstLineDate, position, los);
fprintf('upper left point: Lat = %8.3f , Lon = %8.3f , h = %8.3f m\n',rad2deg(upLeftPoint.getLatitude()), rad2deg(upLeftPoint.getLongitude()),upLeftPoint.getAltitude() )
end
function satelliteQList=addSatelliteQ( gps, satelliteQList ,absDate,q0, q1, q2, q3)
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
attitudeDate = AbsoluteDate(absDate, gps);
rotation = Rotation(q0, q1, q2, q3, true);
rotationRate = Vector3D.ZERO;
rotationAcceleration = Vector3D.ZERO;
pair = TimeStampedAngularCoordinates(attitudeDate, rotation, rotationRate, rotationAcceleration);
satelliteQList.add(pair);
end
function satellitePVList= addSatellitePV( gps, eme2000, itrf, satellitePVList, absDate, px, py, pz, vx, vy, vz)
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.utils.TimeStampedPVCoordinates;
import org.orekit.utils.PVCoordinates;
import org.orekit.frames.Transform;
ephemerisDate = AbsoluteDate(absDate, gps);
position = Vector3D(px, py, pz);
velocity = Vector3D(vx, vy, vz);
pvITRF = PVCoordinates(position, velocity);
transform = itrf.getTransformTo(eme2000, ephemerisDate);
pvEME2000 = transform.transformPVCoordinates(pvITRF);
satellitePVList.add( TimeStampedPVCoordinates(ephemerisDate, pvEME2000.getPosition(), pvEME2000.getVelocity(), Vector3D.ZERO));
end
function InverseLocation()
clear all
%Put 'orekit-data.zip' in the current directory, if not I get an error in line 55 %org.orekit.errors.OrekitException: aucune donne d'historique UTC-TAI n'a t charge
% These seems to work if pasted to prompt.
% javaaddpath 'C:\ ... enter your path here ...\MATLAB'
% javaaddpath 'C:\.. enter your path here ...\MATLAB\orekit-7.1.jar'
% javaaddpath 'C:\.. enter your path here ...\\MATLAB\rugged-1.0.jar'
% javaaddpath 'C:\.. enter your path here... \\MATLAB\commons-math3-3.6.1.jar'
%%
import org.orekit.rugged.errors.RuggedException;
import java.util.ArrayList;
import java.util.List;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.rugged.los.*;
import org.orekit.rugged.utils.*;
%% Configure Orekit. The file orekit-data.zip must be in current dir
% Initialize Orekit, assuming an orekit-data folder is in user home directory
import org.orekit.data.ZipJarCrawler
import org.orekit.time.AbsoluteDate
import org.orekit.time.TimeScalesFactory
DM=org.orekit.data.DataProvidersManager.getInstance();
crawler=org.orekit.data.ZipJarCrawler('orekit-data.zip');
DM.clearProviders();
DM.addProvider(crawler);
%% Building of the LOS
%The raw viewing direction of pixel i with respect to the instrument is defined by the vector:
rawDirs = ArrayList();
for i =1:2000
%20 field of view, 2000 pixels
rawDirs.add (Vector3D(0,i*deg2rad(20)/2000,1));
end
%The instrument is oriented 10 off nadir around the X-axis, we need to rotate the viewing
%direction to obtain the line of sight in the satellite frame
losBuilder = LOSBuilder(rawDirs);
losBuilder.addTransform(FixedRotation(ParameterType.FIXED, Vector3D.PLUS_I, deg2rad(10)));
lineOfSight = losBuilder.build();
%% Configure the Datation
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScalesFactory;
import org.orekit.rugged.linesensor.LinearLineDatation;
%We use Orekit for handling time and dates, and Rugged for defining the datation model:
utc = TimeScalesFactory.getUTC();
absDate = AbsoluteDate('2009-12-11T16:59:30.0', utc);
lineDatation = LinearLineDatation(absDate, 1, 20);
%% Initialize the Line Sensor using LOS and Datation
import org.orekit.rugged.linesensor.LineSensor;
%With the LOS and the datation now defined , we can initialize a line sensor object in Rugged:
sensorName = 'mySensor';
lineSensor = LineSensor(sensorName, lineDatation, Vector3D.ZERO, lineOfSight);
%% Configure Frames (EME2000 and ITRF)
import org.orekit.frames.*;
import org.orekit.utils.*;
%In our application, we simply need to know the name of the frames we are working with. Positions and
%velocities are given in the ITRF terrestrial frame, while the quaternions are given in EME2000
%inertial frame.
eme2000 = FramesFactory.getEME2000();
simpleEOP = true; % we don't want to compute tiny tidal effects at millimeter level
itrf = FramesFactory.getITRF(IERSConventions.IERS_2010, simpleEOP);
%% Reading Quaternions
satelliteQList = ArrayList();
gps=TimeScalesFactory.getGPS();
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:58:42.592937', -0.340236, 0.333952, -0.844012, -0.245684);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:06.592937', -0.354773, 0.329336, -0.837871, -0.252281);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:30.592937', -0.369237, 0.324612, -0.831445, -0.258824);
addSatelliteQ(gps, satelliteQList, '2009-12-11T16:59:54.592937', -0.3836, 0.319792, -0.824743, -0.265299);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:00:18.592937', -0.397834, 0.314883, -0.817777, -0.271695);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:00:42.592937', -0.411912, 0.309895, -0.810561, -0.278001);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:06.592937', -0.42581, 0.304838, -0.803111, -0.284206);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:30.592937', -0.439505, 0.299722, -0.795442, -0.290301);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:01:54.592937', -0.452976, 0.294556, -0.787571, -0.296279);
addSatelliteQ(gps, satelliteQList, '2009-12-11T17:02:18.592937', -0.466207, 0.28935, -0.779516, -0.302131);
%% Reading Potitions/Velocities
satellitePVList = ArrayList();
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:58:42.592937', -726361.466, -5411878.485, 4637549.599, -2463.635, -4447.634, -5576.736);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:04.192937', -779538.267, -5506500.533, 4515934.894, -2459.848, -4312.676, -5683.906);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:25.792937', -832615.368, -5598184.195, 4392036.13, -2454.395, -4175.564, -5788.201);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T16:59:47.392937', -885556.748, -5686883.696, 4265915.971, -2447.273, -4036.368, -5889.568);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:08.992937', -938326.32, -5772554.875, 4137638.207, -2438.478, -3895.166, -5987.957);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:30.592937', -990887.942, -5855155.21, 4007267.717, -2428.011, -3752.034, -6083.317);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:00:52.192937', -1043205.448, -5934643.836, 3874870.441, -2415.868, -3607.05, -6175.6);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:13.792937', -1095242.669, -6010981.571, 3740513.34, -2402.051, -3460.291, -6264.76);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:35.392937', -1146963.457, -6084130.93, 3604264.372, -2386.561, -3311.835, -6350.751);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:01:56.992937', -1198331.706, -6154056.146, 3466192.446, -2369.401, -3161.764, -6433.531);
addSatellitePV(gps, eme2000, itrf, satellitePVList, '2009-12-11T17:02:18.592937', -1249311.381, -6220723.191, 3326367.397, -2350.574, -3010.159, -6513.056);
%% Configure and Build Rugged
import org.orekit.rugged.api.*;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.utils.*;
rugged=RuggedBuilder();
rugged.setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
rugged.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
rugged.setTimeSpan(absDate, absDate.shiftedBy(60.0), 0.01, 5 / lineSensor.getRate(0));
rugged.setTrajectory(InertialFrameId.EME2000,...
satellitePVList, 4, CartesianDerivativesFilter.USE_P,...
satelliteQList, 4, AngularDerivativesFilter.USE_R);
rugged.addLineSensor(lineSensor);
Rugged=rugged.build();
%% Geodetic Point creation and Inverse Location
%Point defined by its latitude, longitude and altitude
import org.orekit.bodies.GeodeticPoint;
latitude = deg2rad(34.27452);
longitude = deg2rad(-99.56804);
altitude = 0.0;
gp=GeodeticPoint(latitude, longitude, altitude);
% Search the sensor pixel seeing point
% the obteined result must be (1000,1000).
% the above geodetic point coordinates are obteined using DirecLocation.m to
% project the image point (1000,1000) on the ground.
minLine = 950;
maxLine = 1050;
sensorPixel = Rugged.inverseLocation(sensorName, gp, minLine, maxLine);
%% Test of the result and Print outputs
%we need to test if the sensor pixel is found in the prescribed lines
%otherwise the sensor pixel is empty
if (isempty(sensorPixel))
fprintf('Sensor Pixel is Empty: point cannot be seen between the prescribed line numbers\n')
else
fprintf('Sensor Pixel found : line = %5.3f, pixel = %5.3f \n', sensorPixel.getLineNumber(), sensorPixel.getPixelNumber())
%Find the date at which the sensor sees the ground point
dateLine = Rugged.dateLocation(sensorName, gp, minLine, maxLine);
fprintf(['Date at which the sensor sees the ground point :', char(dateLine.toString()),'\n'])
end
end
%% read Quaternions Function
function satelliteQList=addSatelliteQ( gps, satelliteQList ,absDate,q0, q1, q2, q3)
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
attitudeDate = AbsoluteDate(absDate, gps);
rotation = Rotation(q0, q1, q2, q3, true);
rotationRate = Vector3D.ZERO;
rotationAcceleration = Vector3D.ZERO;
pair = TimeStampedAngularCoordinates(attitudeDate, rotation, rotationRate, rotationAcceleration);
satelliteQList.add(pair);
end
%% read Position/Velocity Function
function satellitePVList= addSatellitePV( gps, eme2000, itrf, satellitePVList, absDate, px, py, pz, vx, vy, vz)
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.utils.TimeStampedPVCoordinates;
import org.orekit.utils.PVCoordinates;
import org.orekit.frames.Transform;
ephemerisDate = AbsoluteDate(absDate, gps);
position = Vector3D(px, py, pz);
velocity = Vector3D(vx, vy, vz);
pvITRF = PVCoordinates(position, velocity);
transform = itrf.getTransformTo(eme2000, ephemerisDate);
pvEME2000 = transform.transformPVCoordinates(pvITRF);
satellitePVList.add( TimeStampedPVCoordinates(ephemerisDate, pvEME2000.getPosition(), pvEME2000.getVelocity(), Vector3D.ZERO));
end
%In this example we aim to create the rugged object based on the DIM file (in xml format).
%Dimap is a format file used to provide interior and exterior orientation
%elements, this format is used by several satellites such: SPOT5,
%Formosat, THEOS, ALSAT-2A, KOMPSAT-2 and other.
%Except SPOT5 and Formosat, the interior orientation parameters are
%given in the form of polynomial coefficients that allow the estimation of the
%look direction of a considered pixel in a frame called RLOS and also the
%Bias angles to transform the look directions from RLOS to RSAT.
%(see: DOI 10.1007/s12524-014-0380-x and doi:10.5194/isprsarchives-XL-1-W1-35-2013)
%as an example for THEOS Dimap file see:
%http://ortho-qgis.googlecode.com/svn/trunk/Chiangmai1Dimap.xml
%This example has been tested and works also using ALSAT-2A DIM file.
function dim2rugged()
clear all
%Put 'orekit-data.zip' in the current directory, if not I get an error in line 55 %org.orekit.errors.OrekitException: aucune donnée d'historique UTC-TAI n'a été chargée
% These seems to work if pasted to prompt.
% javaaddpath 'C:\ ... enter your path here ...\MATLAB'
% javaaddpath 'C:\.. enter your path here ...\MATLAB\orekit-7.1.jar'
% javaaddpath 'C:\.. enter your path here ...\\MATLAB\rugged-1.0.jar'
% javaaddpath 'C:\.. enter your path here... \\MATLAB\commons-math3-3.6.1.jar'
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
dimFile='Chiangmai1Dimap.xml';
%terrainaltitude is the altitude of the ground intersection point
terrainAltitude=800;
%this function returns a RuggedBuilder based on DIM file and a nominal terrainAltitude
ruggedBuilder= Dim2RuggedBuilderObj(dimFile,terrainAltitude);
%the terrainAltitude can be changed using ruggedBuilder.setConstantElevation(terrainAltitude);
%then dimRugged=ruggedBuilder.build(); must be called to create a new Rugged that
%allow the direct location at a different terrain altitude without parsing
%the DIM file again.
dimRugged=ruggedBuilder.build();
%This exemple consider the PAN image only where the sensor line is called
%PAN Sensor
lineSensor=dimRugged.getLineSensor('PAN Sensor');
%Get the LOS and the datation of the first pixel of the image
position = lineSensor.getPosition();
lineDate = lineSensor.getDate(0);
los = lineSensor.getLos(lineDate, 0);
%Get the corresponding ground coordinates of the considered pixel at terrainAltitude
upLeftPoint = dimRugged.directLocation(lineDate, position, los);
%Print the results
fprintf('upper left point: Lat = %8.6f °, Lon = %8.6f °, h = %8.2f m\n',rad2deg(upLeftPoint.getLatitude()), rad2deg(upLeftPoint.getLongitude()),upLeftPoint.getAltitude() )
end
function ruggedBuilder= Dim2RuggedBuilderObj(dimFile,terrainAltitude)
% This function creates a RuggedBuilder object based on DIM file
% The intersection are done at terrainAltitude, when this object is used for DirectLocation
%% Configure Orekit. The file orekit-data.zip must be in current dir
import org.orekit.data.ZipJarCrawler
import org.orekit.time.AbsoluteDate
import org.orekit.time.TimeScalesFactory
DM=org.orekit.data.DataProvidersManager.getInstance();
crawler=org.orekit.data.ZipJarCrawler('orekit-data.zip');
DM.clearProviders();
DM.addProvider(crawler);
%%
%Read XML document and get Document Object Model node
xDoc = xmlread(dimFile);
%REFERENCE_TIME is the time of imaging of the REFERENCE_LINE
Element='REFERENCE_TIME';
referenceTime=GetElementValue(Element,xDoc);
%FormatTime to get the read time in the standard format
referenceTime=FormatTime(referenceTime);
%LINE_PERIOD is the time required to record an image line
Element='LINE_PERIOD';
%LineRate is the inverse of the line period
lineRate=1/(str2double(GetElementValue(Element,xDoc)));
%REFERENCE_LINE the line used for datation reference
Element='REFERENCE_LINE';
referenceLine=str2double(GetElementValue(Element,xDoc));
%NROWS the number of Rows
Element='NROWS';
nRows=str2double(GetElementValue(Element,xDoc));
%NCOLS the number of columns
Element='NCOLS';
nCols=str2double(GetElementValue(Element,xDoc));
%YAW, PITCH, ROLL are the angles between RLOS and RSAT, where RLOS is the
%frame where the los are measured and RSAT is the frame tied to the
%spacecraft where the quatenions represent the rotaion between RSAT and
%EME2000
Element='YAW';
yaw=str2double(GetElementValue(Element,xDoc));
Element='PITCH';
pitch=str2double(GetElementValue(Element,xDoc));
Element='ROLL';
roll=str2double(GetElementValue(Element,xDoc));
%XLOS_i and YLOS_i are the polynomial coefficiens that allow the
%calculation of LOS direction of each pixel in RLOS
%(see: DOI 10.1007/s12524-014-0380-x)
Element='XLOS_3';
xLosPoly=str2double(GetElementValue(Element,xDoc));
Element='XLOS_2';
xLosPoly=[xLosPoly, str2double(GetElementValue(Element,xDoc))];
Element='XLOS_1';
xLosPoly=[xLosPoly, str2double(GetElementValue(Element,xDoc))];
Element='XLOS_0';
xLosPoly=[xLosPoly, str2double(GetElementValue(Element,xDoc))];
Element='YLOS_3';
yLosPoly=str2double(GetElementValue(Element,xDoc));
Element='YLOS_2';
yLosPoly=[yLosPoly, str2double(GetElementValue(Element,xDoc))];
Element='YLOS_1';
yLosPoly=[yLosPoly, str2double(GetElementValue(Element,xDoc))];
Element='YLOS_0';
yLosPoly=[yLosPoly, str2double(GetElementValue(Element,xDoc))];
%%
quaternions = xDoc.getElementsByTagName('Quaternion');
%read the Quaternions into the arraylist
satelliteQList=ParseQuaternions(quaternions);
%%
pv = xDoc.getElementsByTagName('Point');
%read the Positions/Velocities into the arraylist
satellitePVList=ParsePV(pv);
%%
%Build the LOS based on whole pushbroom size (ncols), the polynomial
%describing the LOS and bias angles (yaw,pitch,roll)
lineOfSight=LosBuilding(nCols,xLosPoly,yLosPoly,yaw,pitch,roll);
%%
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScalesFactory;
import org.orekit.rugged.linesensor.LinearLineDatation;
%setup of the datation
gps = TimeScalesFactory.getGPS();
absDate = AbsoluteDate(referenceTime, gps);
lineDatation = LinearLineDatation(absDate, referenceLine, lineRate);
%%
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.rugged.linesensor.LineSensor;
%With the LOS and the datation now defined , we can initialize a line sensor object in Rugged:
lineSensor = LineSensor('PAN Sensor', lineDatation, Vector3D.ZERO, lineOfSight);
%%
import org.orekit.rugged.api.*;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.utils.*;
ruggedBuilder=RuggedBuilder();
%the intersection during the direct location will be at "terrainAltitude"
ruggedBuilder.setConstantElevation(terrainAltitude);
ruggedBuilder.setAlgorithm(AlgorithmId.CONSTANT_ELEVATION_OVER_ELLIPSOID);
ruggedBuilder.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
captureDuration=(nRows+100)/ lineSensor.getRate(0);
ruggedBuilder.setTimeSpan(absDate, absDate.shiftedBy(captureDuration), 0.001, 5 / lineSensor.getRate(0));
ruggedBuilder.setTrajectory(InertialFrameId.EME2000,...
satellitePVList, 4, CartesianDerivativesFilter.USE_P,...
satelliteQList, 4, AngularDerivativesFilter.USE_R);
ruggedBuilder.addLineSensor(lineSensor);
end
function lineOfSight=LosBuilding(nCols,xLosPoly,yLosPoly,yaw,pitch,roll)
import java.util.ArrayList;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.rugged.los.*;
import org.orekit.rugged.utils.*;
rawDirs = ArrayList();
for i =1:nCols
psiY = -polyval(xLosPoly,i)/1000;
psiX = polyval(yLosPoly,i)/1000;
rawDirs.add (Vector3D(psiX,psiY,1));
end
losBuilder = LOSBuilder(rawDirs);
losBuilder.addTransform(FixedRotation(ParameterType.FIXED, Vector3D.PLUS_K,yaw));
losBuilder.addTransform(FixedRotation(ParameterType.FIXED, Vector3D.PLUS_J,pitch));
losBuilder.addTransform(FixedRotation(ParameterType.FIXED, Vector3D.PLUS_I,roll));
lineOfSight = losBuilder.build();
end
function valElement=GetElementValue(element,xDoc)
% valElement=GetElementValue(element,xDoc) returne a string contained in
% the corresponding "element" in the XML "xDoc" file
valElement=char(xDoc.getElementsByTagName(element).item(0).getTextContent);
end
function time=FormatTime(time)
%FormatTime replace the space contained the time string by "T"
position=strfind(time,' ');
time(position)='T';
end
function satellitePVList=ParsePV(pv)
%ParsePV parse the "Point" element in the dimap file to get an ArrayList
import java.util.ArrayList;
import java.util.List;
import org.orekit.time.TimeScalesFactory;
import org.orekit.frames.*;
import org.orekit.utils.*;
satellitePVList = ArrayList();
gps=TimeScalesFactory.getGPS();
eme2000 = FramesFactory.getEME2000();
simpleEOP = true; % we don't want to compute tiny tidal effects at millimeter level
itrf = FramesFactory.getITRF(IERSConventions.IERS_2010, simpleEOP);
nPV = pv.getLength;
position=[];
velocity=[];
for i=0:nPV - 1
entries = pv.item(i).getChildNodes;
node = entries.getFirstChild;
while ~isempty(node)
if strcmpi(node.getNodeName, 'TIME')
T= FormatTime(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Location')
position= str2num(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Velocity')
velocity= str2num(char(node.getTextContent));
end
node = node.getNextSibling;
end
addSatellitePV(gps, eme2000, itrf, satellitePVList, T, position(1), position(2), position(3), velocity(1), velocity(2), velocity(3));
end
end
function satelliteQList=ParseQuaternions(quaternions)
%ParseQuaternions parse the "Quaternion" element in the dimap file to get an ArrayList
import java.util.ArrayList;
import java.util.List;
import org.orekit.time.TimeScalesFactory;
satelliteQList = ArrayList();
gps=TimeScalesFactory.getGPS();
nQuaternions=quaternions.getLength;
for i=0:nQuaternions - 1
entries = quaternions.item(i).getChildNodes;
node = entries.getFirstChild;
while ~isempty(node)
if strcmpi(node.getNodeName, 'TIME')
T= FormatTime(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Q0')
Q0= str2double(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Q1')
Q1= str2double(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Q2')
Q2= str2double(char(node.getTextContent));
end
if strcmpi(node.getNodeName, 'Q3')
Q3= str2double(char(node.getTextContent));
end
node = node.getNextSibling;
end
addSatelliteQ(gps, satelliteQList, T, Q0, Q1, Q2, Q3);
end
end
function satelliteQList=addSatelliteQ( gps, satelliteQList ,absDate,q0, q1, q2, q3)
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
attitudeDate = AbsoluteDate(absDate, gps);
rotation = Rotation(q0, q1, q2, q3, true);
rotationRate = Vector3D.ZERO;
rotationAcceleration = Vector3D.ZERO;
pair = TimeStampedAngularCoordinates(attitudeDate, rotation, rotationRate, rotationAcceleration);
satelliteQList.add(pair);
end
function satellitePVList= addSatellitePV( gps, eme2000, itrf, satellitePVList, absDate, px, py, pz, vx, vy, vz)
import org.orekit.time.AbsoluteDate;
import org.apache.commons.math3.geometry.euclidean.threed.Rotation;
import org.apache.commons.math3.geometry.euclidean.threed.Vector3D;
import org.orekit.utils.TimeStampedPVCoordinates;
import org.orekit.utils.PVCoordinates;
import org.orekit.frames.Transform;
ephemerisDate = AbsoluteDate(absDate, gps);
position = Vector3D(px, py, pz);
velocity = Vector3D(vx, vy, vz);
pvITRF = PVCoordinates(position, velocity);
transform = itrf.getTransformTo(eme2000, ephemerisDate);
pvEME2000 = transform.transformPVCoordinates(pvITRF);
satellitePVList.add( TimeStampedPVCoordinates(ephemerisDate, pvEME2000.getPosition(), pvEME2000.getVelocity(), Vector3D.ZERO));
end
<?xml version="1.0" encoding="UTF-8"?>
<!--
Copyright 2013-2016 CS Systèmes d'Information
Copyright 2013-2022 CS GROUP
Licensed 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
......@@ -15,13 +15,13 @@
-->
<project name="Rugged">
<bannerLeft>
<name>CS Syst&#232;mes d&#039;Information</name>
<src>/images/logo_cs_2008_baseline_ang.jpg</src>
<href>http://www.c-s.fr/</href>
<name>CS GROUP</name>
<src>/images/logo_cs_group.png</src>
<href>https://www.csgroup.eu/</href>
</bannerLeft>
<bannerRight>
<name>Rugged</name>
<src>/images/rugged-logo.png</src>
<src>/images/rugged-logo-small.jpg</src>
<href>/index.html</href>
</bannerRight>
<body>
......@@ -31,28 +31,29 @@
<item name="Building" href="/building.html" />
<item name="Configuration" href="/configuration.html" />
<item name="FAQ" href="/faq.html" />
<item name="License" href="/license.html" />
<item name="License" href="/licenses.html" />
<item name="Downloads" href="/downloads.html" />
<item name="Changes" href="/changes-report.html" />
<item name="Contact" href="/contact.html" />
</menu>
<menu name="Design">
<item name="Overview" href="/design/overview.html" />
<item name="Technical choices" href="/design/technical-choices.html" />
<item name="Digital Elevation Model" href="/design/digital-elevation-model.html" />
<item name="Preliminary design" href="/design/preliminary-design.html" />
<item name="Overview" href="/design/overview.html" />
<item name="Technical choices" href="/design/technical-choices.html" />
<item name="Digital Elevation Model" href="/design/digital-elevation-model.html" />
<item name="Design of the major functions" href="/design/design-major-functions.html" />
</menu>
<menu name="Tutorials">
<item name="Direct location" href="/tutorials/direct-location.html" />
<item name="Direct location with DEM" href="/tutorials/direct-location-with-DEM.html" />
<item name="Inverse location" href="/tutorials/inverse-location.html" />
<item name="Tile Updater" href="/tutorials/tile-updater.html" />
<item name="Matlab examples" href="/tutorials/matlab-example.html" />
</menu>
<menu name="Development">
<item name="Contributing" href="/contributing.html" />
<item name="Guidelines" href="/guidelines.html" />
<item name="Javadoc" href="/apidocs/index.html" />
</menu>
<item name="Release guide" href="/release-guide.html" />
</menu>
<menu ref="reports"/>
</body>
<poweredBy>
......
/* 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,21 +17,28 @@
package org.orekit.rugged;
import static org.junit.Assert.assertEquals;
import java.lang.reflect.Field;
import java.lang.reflect.Modifier;
import java.util.ArrayList;
import java.util.List;
import java.util.Map;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.ode.nonstiff.DormandPrince853Integrator;
import org.hipparchus.util.FastMath;
import java.util.ArrayList;
import java.util.List;
import org.junit.Assert;
import org.orekit.attitudes.AttitudeProvider;
import org.orekit.attitudes.NadirPointing;
import org.orekit.attitudes.YawCompensation;
import org.orekit.bodies.BodyShape;
import org.orekit.bodies.CelestialBodyFactory;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.bodies.OneAxisEllipsoid;
import org.orekit.errors.OrekitException;
import org.orekit.data.DataContext;
import org.orekit.forces.gravity.HolmesFeatherstoneAttractionModel;
import org.orekit.forces.gravity.ThirdBodyAttraction;
import org.orekit.forces.gravity.potential.GravityFieldFactory;
......@@ -40,6 +47,10 @@ import org.orekit.frames.Frame;
import org.orekit.frames.FramesFactory;
import org.orekit.frames.Transform;
import org.orekit.orbits.CircularOrbit;
import org.orekit.orbits.FieldCartesianOrbit;
import org.orekit.orbits.FieldCircularOrbit;
import org.orekit.orbits.FieldEquinoctialOrbit;
import org.orekit.orbits.FieldKeplerianOrbit;
import org.orekit.orbits.Orbit;
import org.orekit.orbits.OrbitType;
import org.orekit.orbits.PositionAngle;
......@@ -47,7 +58,9 @@ import org.orekit.propagation.Propagator;
import org.orekit.propagation.SpacecraftState;
import org.orekit.propagation.analytical.KeplerianPropagator;
import org.orekit.propagation.numerical.NumericalPropagator;
import org.orekit.propagation.sampling.OrekitFixedStepHandler;
import org.orekit.propagation.semianalytical.dsst.utilities.JacobiPolynomials;
import org.orekit.propagation.semianalytical.dsst.utilities.NewcombOperators;
import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.rugged.los.LOSBuilder;
import org.orekit.rugged.los.TimeDependentLOS;
import org.orekit.time.AbsoluteDate;
......@@ -59,13 +72,92 @@ import org.orekit.utils.PVCoordinates;
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.utils.TimeStampedPVCoordinates;
/**
* @author Luc Maisonobe
* @author Guylaine Prat
*/
public class TestUtils {
/**
* Clean up of factories for JUnit
* TBN: copied from Utils of Test suite of Orekit 9.0
* @since 2.0
*/
public static void clearFactories() {
clearFactoryMaps(CelestialBodyFactory.class);
CelestialBodyFactory.clearCelestialBodyLoaders();
clearFactoryMaps(FramesFactory.class);
clearFactoryMaps(TimeScalesFactory.class);
clearFactory(TimeScalesFactory.class, TimeScale.class);
clearFactoryMaps(FieldCartesianOrbit.class);
clearFactoryMaps(FieldKeplerianOrbit.class);
clearFactoryMaps(FieldCircularOrbit.class);
clearFactoryMaps(FieldEquinoctialOrbit.class);
clearFactoryMaps(JacobiPolynomials.class);
clearFactoryMaps(NewcombOperators.class);
for (final Class<?> c : NewcombOperators.class.getDeclaredClasses()) {
if (c.getName().endsWith("PolynomialsGenerator")) {
clearFactoryMaps(c);
}
}
FramesFactory.clearEOPHistoryLoaders();
FramesFactory.setEOPContinuityThreshold(5 * Constants.JULIAN_DAY);
TimeScalesFactory.clearUTCTAIOffsetsLoaders();
GravityFieldFactory.clearPotentialCoefficientsReaders();
GravityFieldFactory.clearOceanTidesReaders();
DataContext.getDefault().getDataProvidersManager().clearProviders();
DataContext.getDefault().getDataProvidersManager().clearLoadedDataNames();
}
/** Clean up of factory map
* @param factoryClass
* @since 2.0
*/
private static void clearFactoryMaps(Class<?> factoryClass) {
try {
for (Field field : factoryClass.getDeclaredFields()) {
if (Modifier.isStatic(field.getModifiers()) &&
Map.class.isAssignableFrom(field.getType())) {
field.setAccessible(true);
((Map<?, ?>) field.get(null)).clear();
}
}
} catch (IllegalAccessException iae) {
Assert.fail(iae.getMessage());
}
}
/** Clean up of a factory
* @param factoryClass
* @param cachedFieldsClass
* @since 2.0
*/
private static void clearFactory(Class<?> factoryClass, Class<?> cachedFieldsClass) {
try {
for (Field field : factoryClass.getDeclaredFields()) {
if (Modifier.isStatic(field.getModifiers()) &&
cachedFieldsClass.isAssignableFrom(field.getType())) {
field.setAccessible(true);
field.set(null, null);
}
}
} catch (IllegalAccessException iae) {
Assert.fail(iae.getMessage());
}
}
/**
* Generate satellite ephemeris.
*/
public static void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf,
ArrayList<TimeStampedPVCoordinates> satellitePVList,
String absDate,
double px, double py, double pz, double vx, double vy, double vz)
throws OrekitException {
double px, double py, double pz, double vx, double vy, double vz) {
AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps);
Vector3D position = new Vector3D(px, py, pz);
Vector3D velocity = new Vector3D(vx, vy, vz);
......@@ -76,8 +168,12 @@ public class TestUtils {
satellitePVList.add(new TimeStampedPVCoordinates(ephemerisDate, pEME2000, vEME2000, Vector3D.ZERO));
}
/**
* Generate satellite attitudes.
*/
public static void addSatelliteQ(TimeScale gps, ArrayList<TimeStampedAngularCoordinates> satelliteQList,
String absDate, double q0, double q1, double q2, double q3) {
AbsoluteDate attitudeDate = new AbsoluteDate(absDate, gps);
Rotation rotation = new Rotation(q0, q1, q2, q3, true);
TimeStampedAngularCoordinates pair =
......@@ -85,20 +181,29 @@ public class TestUtils {
satelliteQList.add(pair);
}
public static BodyShape createEarth()
throws OrekitException {
/** Create an Earth for Junit tests.
*/
public static BodyShape createEarth() {
return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS,
Constants.WGS84_EARTH_FLATTENING,
FramesFactory.getITRF(IERSConventions.IERS_2010, true));
}
public static NormalizedSphericalHarmonicsProvider createGravityField()
throws OrekitException {
/** Created a gravity field.
* @return normalized spherical harmonics coefficients
*/
public static NormalizedSphericalHarmonicsProvider createGravityField() {
return GravityFieldFactory.getNormalizedProvider(12, 12);
}
public static Orbit createOrbit(double mu)
throws OrekitException {
/** Create an orbit.
* @param mu Earth gravitational constant
* @return the orbit
*/
public static Orbit createOrbit(double mu) {
// the following orbital parameters have been computed using
// Orekit tutorial about phasing, using the following configuration:
//
......@@ -119,11 +224,13 @@ public class TestUtils {
FastMath.PI, PositionAngle.TRUE,
eme2000, date, mu);
}
/** Create the propagator of an orbit.
* @return propagator of the orbit
*/
public static Propagator createPropagator(BodyShape earth,
NormalizedSphericalHarmonicsProvider gravityField,
Orbit orbit)
throws OrekitException {
Orbit orbit) {
AttitudeProvider yawCompensation = new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth));
SpacecraftState state = new SpacecraftState(orbit,
......@@ -151,7 +258,11 @@ public class TestUtils {
}
/** Create a perfect Line Of Sight list
* @return the perfect LOS list
*/
public static LOSBuilder createLOSPerfectLine(Vector3D center, Vector3D normal, double halfAperture, int n) {
List<Vector3D> list = new ArrayList<Vector3D>(n);
for (int i = 0; i < n; ++i) {
double alpha = (halfAperture * (2 * i + 1 - n)) / (n - 1);
......@@ -160,8 +271,12 @@ public class TestUtils {
return new LOSBuilder(list);
}
/** Create a Line Of Sight which depends on time.
* @return the dependent of time LOS
*/
public static TimeDependentLOS createLOSCurvedLine(Vector3D center, Vector3D normal,
double halfAperture, double sagitta, int n) {
Vector3D u = Vector3D.crossProduct(center, normal);
List<Vector3D> list = new ArrayList<Vector3D>(n);
for (int i = 0; i < n; ++i) {
......@@ -175,48 +290,113 @@ public class TestUtils {
return new LOSBuilder(list).build();
}
/** Propagate an orbit between 2 given dates
* @return a list of TimeStampedPVCoordinates
*/
public static List<TimeStampedPVCoordinates> orbitToPV(Orbit orbit, BodyShape earth,
AbsoluteDate minDate, AbsoluteDate maxDate,
double step)
throws OrekitException {
AbsoluteDate minDate, AbsoluteDate maxDate,
double step) {
Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)));
propagator.propagate(minDate);
final List<TimeStampedPVCoordinates> list = new ArrayList<TimeStampedPVCoordinates>();
propagator.setMasterMode(step, new OrekitFixedStepHandler() {
public void init(SpacecraftState s0, AbsoluteDate t) {
}
public void handleStep(SpacecraftState currentState, boolean isLast) {
list.add(new TimeStampedPVCoordinates(currentState.getDate(),
currentState.getPVCoordinates().getPosition(),
currentState.getPVCoordinates().getVelocity(),
Vector3D.ZERO));
}
});
propagator.getMultiplexer().add(step, currentState -> list.add(new TimeStampedPVCoordinates(currentState.getDate(),
currentState.getPVCoordinates().getPosition(),
currentState.getPVCoordinates().getVelocity(),
Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
/** Propagate an attitude between 2 given dates
* @return a list of TimeStampedAngularCoordinates
*/
public static List<TimeStampedAngularCoordinates> orbitToQ(Orbit orbit, BodyShape earth,
AbsoluteDate minDate, AbsoluteDate maxDate,
double step)
throws OrekitException {
double step) {
Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)));
propagator.propagate(minDate);
final List<TimeStampedAngularCoordinates> list = new ArrayList<TimeStampedAngularCoordinates>();
propagator.setMasterMode(step, new OrekitFixedStepHandler() {
public void init(SpacecraftState s0, AbsoluteDate t) {
}
public void handleStep(SpacecraftState currentState, boolean isLast) {
list.add(new TimeStampedAngularCoordinates(currentState.getDate(),
currentState.getAttitude().getRotation(),
Vector3D.ZERO, Vector3D.ZERO));
}
});
propagator.getMultiplexer().add(step, currentState -> list.add(new TimeStampedAngularCoordinates(currentState.getDate(),
currentState.getAttitude().getRotation(),
Vector3D.ZERO, Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
/**
* Asserts that two SensorPixel are equal to within a positive delta for each component.
* For more details see:
* org.junit.assert.assertEquals(String message, double expected, double actual, double delta)
*/
static public void sensorPixelAssertEquals(SensorPixel expected, SensorPixel result, double delta) {
assertEquals(null,expected.getLineNumber(), result.getLineNumber(), delta);
assertEquals(null,expected.getPixelNumber(), result.getPixelNumber(), delta);
}
/**
* Tell if two SensorPixel are the same, where each components are equal to within a positive delta.
* For more details see:
* org.junit.assert.assertEquals(String message, double expected, double actual, double delta)
* @param expected expected sensor pixel
* @param result actual sensor pixel
* @param delta delta within two values are consider equal
* @return true if the two SensorPixel are the same, false otherwise
*/
static public Boolean sameSensorPixels(SensorPixel expected, SensorPixel result, double delta) {
Boolean sameSensorPixel = false;
// To have same pixel (true)
sameSensorPixel = !(isDifferent(expected.getLineNumber(), result.getLineNumber(), delta) ||
isDifferent(expected.getPixelNumber(), result.getPixelNumber(), delta));
return sameSensorPixel;
}
/**
* Tell if two SensorPixel are the same, where each components are equal to within a positive delta.
* For more details see:
* org.junit.assert.assertEquals(String message, double expected, double actual, double delta)
* @param expected expected sensor pixel
* @param result actual sensor pixel
* @param delta delta within two values are consider equal
* @return true if the two SensorPixel are the same, false otherwise
*/
static public Boolean sameGeodeticPoints(GeodeticPoint expected, GeodeticPoint result, double delta) {
Boolean sameGeodeticPoint = false;
// To have same GeodeticPoint (true)
sameGeodeticPoint = !(isDifferent(expected.getLatitude(), result.getLatitude(), delta) ||
isDifferent(expected.getLongitude(), result.getLongitude(), delta) ||
isDifferent(expected.getAltitude(), result.getAltitude(), delta));
return sameGeodeticPoint;
}
/** Return true if two double values are different within a positive delta.
* @param val1 first value to compare
* @param val2 second value to compare
* @param delta delta within the two values are consider equal
* @return true is different, false if equal within the positive delta
*/
static private boolean isDifferent(double val1, double val2, double delta) {
if (Double.compare(val1, val2) == 0) {
return false;
}
if ((FastMath.abs(val1 - val2) <= delta)) {
return false;
}
return true;
}
}
/* 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.adjustment;
import java.lang.reflect.Field;
import java.util.ArrayList;
import java.util.Iterator;
import java.util.List;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum;
import org.junit.After;
import org.junit.Assert;
import org.junit.Before;
import org.junit.Test;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.measurements.SensorMapping;
import org.orekit.rugged.adjustment.util.InitInterRefiningTest;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.linesensor.SensorPixel;
public class AdjustmentContextTest {
@Before
public void setUp() {
try {
// One must set a context for the adjustment ... Here we choose an inter sensors optimization problem
InitInterRefiningTest refiningTest = new InitInterRefiningTest();
refiningTest.initRefiningTest();
ruggedList = refiningTest.getRuggedList();
int lineSampling = 1000;
int pixelSampling = 1000;
double earthConstraintWeight = 0.1;
measurements = refiningTest.generateNoisyPoints(lineSampling, pixelSampling, earthConstraintWeight, false);
} catch (RuggedException re) {
Assert.fail(re.getLocalizedMessage());
}
}
@Test
public void testAdjustmentContext() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements);
// Check if the default OptimizerId is the expected one (use reflectivity)
Field optimizerId = adjustmentContext.getClass().getDeclaredField("optimizerID");
optimizerId.setAccessible(true);
OptimizerId defaultOptimizerId = (OptimizerId) optimizerId.get(adjustmentContext);
Assert.assertTrue((defaultOptimizerId == OptimizerId.GAUSS_NEWTON_QR));
// Check if the change of the default OptimizerId is correct
adjustmentContext.setOptimizer(OptimizerId.GAUSS_NEWTON_LU);
OptimizerId modifiedOptimizerId = (OptimizerId) optimizerId.get(adjustmentContext);
Assert.assertTrue((modifiedOptimizerId == OptimizerId.GAUSS_NEWTON_LU));
// Check if the change of the default OptimizerId is correct
adjustmentContext.setOptimizer(OptimizerId.LEVENBERG_MARQUADT);
modifiedOptimizerId = (OptimizerId) optimizerId.get(adjustmentContext);
Assert.assertTrue((modifiedOptimizerId == OptimizerId.LEVENBERG_MARQUADT));
}
@Test
public void testEstimateFreeParameters() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements);
for (OptimizerId optimizer : OptimizerId.values()) {
// Set the optimizer
adjustmentContext.setOptimizer(optimizer);
List<String> ruggedNameList = new ArrayList<String>();
for(Rugged rugged : ruggedList) {
ruggedNameList.add(rugged.getName());
}
final int maxIterations = 120;
final double convergenceThreshold = 1.e-7;
Optimum optimum = adjustmentContext.estimateFreeParameters(ruggedNameList, maxIterations, convergenceThreshold);
Field optimizerId = adjustmentContext.getClass().getDeclaredField("optimizerID");
optimizerId.setAccessible(true);
OptimizerId usedOptimizerId = (OptimizerId) optimizerId.get(adjustmentContext);
if (usedOptimizerId == OptimizerId.GAUSS_NEWTON_QR || usedOptimizerId == OptimizerId.GAUSS_NEWTON_LU) {
// For Gauss Newton, the number of evaluations is equal to the number of iterations
Assert.assertTrue(optimum.getEvaluations() == optimum.getIterations());
} else if (usedOptimizerId == OptimizerId.LEVENBERG_MARQUADT) {
// For Levenberg Marquadt, the number of evaluations is slightly greater than the number of iterations
Assert.assertTrue(optimum.getEvaluations() >= optimum.getIterations());
}
} // loop on OptimizerId
}
@Test
public void testInvalidRuggedName() {
try {
AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements);
List<String> ruggedNameList = new ArrayList<String>();
// the list must not have a null value
Iterator<Rugged> it = ruggedList.iterator();
while (it.hasNext()) {
ruggedNameList.add(null);
it.next();
}
final int maxIterations = 1;
final double convergenceThreshold = 1.e-7;
adjustmentContext.estimateFreeParameters(ruggedNameList, maxIterations, convergenceThreshold);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getSpecifier());
}
}
@Test
public void testUnsupportedRefiningContext() {
try {
AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements);
List<String> ruggedNameList = new ArrayList<String>();
// Add too many rugged name: the list must have 1 or 2 items
for(Rugged rugged : ruggedList) {
ruggedNameList.add(rugged.getName());
ruggedNameList.add(rugged.getName());
ruggedNameList.add(rugged.getName());
}
final int maxIterations = 1;
final double convergenceThreshold = 1.e-7;
adjustmentContext.estimateFreeParameters(ruggedNameList, maxIterations, convergenceThreshold);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.UNSUPPORTED_REFINING_CONTEXT,re.getSpecifier());
}
}
@Test
public void testSensorMapping() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
String sensorGiven = "lineSensor";
String ruggedGiven = "Rugged";
SensorMapping<SensorPixel> simpleMapping = new SensorMapping<SensorPixel>(sensorGiven) ;
Field ruggedField = simpleMapping.getClass().getDeclaredField("ruggedName");
ruggedField.setAccessible(true);
String ruggedRead = (String) ruggedField.get(simpleMapping);
Field sensorField = simpleMapping.getClass().getDeclaredField("sensorName");
sensorField.setAccessible(true);
String sensorRead = (String) sensorField.get(simpleMapping);
Assert.assertTrue(ruggedGiven.equals(ruggedRead));
Assert.assertTrue(sensorGiven.equals(sensorRead));
}
@After
public void tearDown() {
measurements = null;
ruggedList = null;
}
private Observables measurements;
private List<Rugged> ruggedList;
}
package org.orekit.rugged.adjustment;
import java.lang.reflect.Field;
import java.util.ArrayList;
import java.util.Collection;
import java.util.Collections;
import java.util.Iterator;
import java.util.List;
import java.util.Map.Entry;
import java.util.Set;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum;
import org.junit.After;
import org.junit.Assert;
import org.junit.Before;
import org.junit.Test;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping;
import org.orekit.rugged.adjustment.util.InitGroundRefiningTest;
import org.orekit.rugged.adjustment.util.RefiningParametersDriver;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.SensorPixel;
public class GroundOptimizationProblemBuilderTest {
@Before
public void setUp() {
try {
refiningTest = new InitGroundRefiningTest();
refiningTest.initGroundRefiningTest();
rugged = refiningTest.getRugged();
// get the only line sensor
LineSensor sensor = rugged.getLineSensors().iterator().next();
sensorName = sensor.getName();
measurements = refiningTest.generateNoisyPoints(lineSampling, pixelSampling, false);
numberOfParameters = refiningTest.getParameterToAdjust();
} catch (RuggedException re) {
Assert.fail(re.getLocalizedMessage());
}
}
@Test
public void testEstimateFreeParameters() {
AdjustmentContext adjustmentContext = new AdjustmentContext(Collections.singletonList(rugged), measurements);
final int maxIterations = 50;
final double convergenceThreshold = 1.e-11;
Optimum optimum = adjustmentContext.estimateFreeParameters(Collections.singletonList(rugged.getName()), maxIterations, convergenceThreshold);
Assert.assertTrue(optimum.getIterations() < maxIterations);
// The default optimizer is a Gauss Newton.
// For Gauss Newton, the number of evaluations is equal to the number of iterations
Assert.assertTrue(optimum.getEvaluations() == optimum.getIterations());
final double expectedMaxValue = 39200.0;
Assert.assertEquals(expectedMaxValue, optimum.getResiduals().getMaxValue(), 1.0e-6);
final double expectedRMS = 5067.112098;
Assert.assertEquals(expectedRMS, optimum.getRMS(), 1.0e-6);
final double expectedCost = 286639.1460351976;
Assert.assertEquals(expectedCost, optimum.getCost(), 1.0e-6);
Assert.assertTrue(numberOfParameters == optimum.getPoint().getDimension());
final int sensorToGroundMappingSize = 1600;
Collection<SensorToGroundMapping> ssm = measurements.getGroundMappings();
Iterator<SensorToGroundMapping> it = ssm.iterator();
while (it.hasNext()) {
SensorToGroundMapping ssmit = it.next();
Assert.assertTrue(sensorToGroundMappingSize == ssmit.getMapping().size());
}
Assert.assertTrue(sensorToGroundMappingSize*2 == optimum.getResiduals().getDimension());
}
@Test
public void testNoParametersSelected() {
try {
RefiningParametersDriver.unselectRoll(rugged, sensorName);
RefiningParametersDriver.unselectPitch(rugged, sensorName);
AdjustmentContext adjustmentContext = new AdjustmentContext(Collections.singletonList(rugged), measurements);
final int maxIterations = 50;
final double convergenceThreshold = 1.e-11;
adjustmentContext.estimateFreeParameters(Collections.singletonList(rugged.getName()), maxIterations, convergenceThreshold);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.NO_PARAMETERS_SELECTED,re.getSpecifier());
}
}
@Test
public void testNoReferenceMapping() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
try {
final int maxIterations = 50;
final double convergenceThreshold = 1.e-11;
final List<LineSensor> selectedSensors = new ArrayList<LineSensor>();
selectedSensors.addAll(rugged.getLineSensors());
final GroundOptimizationProblemBuilder groundOptimizationProblem =
new GroundOptimizationProblemBuilder(selectedSensors, measurements, rugged);
Field sensorToGroundMapping = groundOptimizationProblem.getClass().getDeclaredField("sensorToGroundMappings");
sensorToGroundMapping.setAccessible(true);
sensorToGroundMapping.set(groundOptimizationProblem,new ArrayList<SensorToGroundMapping>());
groundOptimizationProblem.build(maxIterations, convergenceThreshold);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.NO_REFERENCE_MAPPINGS,re.getSpecifier());
}
}
@Test
public void testDefaultRuggedName(){
// Get the measurements as computed in other tests
Collection<SensorToGroundMapping> sensorToGroundMapping = measurements.getGroundMappings();
int nbModels = measurements.getNbModels();
// Recompute the measurements in another way ... but that must be the same after all
Observables measurementsNoName = refiningTest.generateNoisyPoints(lineSampling, pixelSampling, true);
Collection<SensorToGroundMapping> sensorToGroundMappingNoName = measurementsNoName.getGroundMappings();
int nbModelsWithWeight = measurementsNoName.getNbModels();
// Compare the two collections of measurements
Assert.assertEquals(nbModels, nbModelsWithWeight);
Assert.assertEquals(sensorToGroundMapping.size(), sensorToGroundMappingNoName.size());
// There is only one item
SensorToGroundMapping arraySensorToGroundMapping = (SensorToGroundMapping) sensorToGroundMapping.toArray()[0];
SensorToGroundMapping arraySensorToGroundMappingNoName = (SensorToGroundMapping) sensorToGroundMappingNoName.toArray()[0];
// Check if the two set are the same
Set<Entry<SensorPixel, GeodeticPoint>> mapping = arraySensorToGroundMapping.getMapping();
Set<Entry<SensorPixel, GeodeticPoint>> mappingNoName = arraySensorToGroundMappingNoName.getMapping();
Iterator<Entry<SensorPixel, GeodeticPoint>> itMapping = mapping.iterator();
while(itMapping.hasNext()) {
Entry<SensorPixel, GeodeticPoint> current = itMapping.next();
SensorPixel key = current.getKey();
GeodeticPoint value = current.getValue();
// Will search in mappingNoName if we can find the (key,value) found in mapping
Boolean found = false;
Iterator<Entry<SensorPixel, GeodeticPoint>> itMappingNoName = mappingNoName.iterator();
while(itMappingNoName.hasNext()) {
Entry<SensorPixel, GeodeticPoint> currentNoName = itMappingNoName.next();
SensorPixel keyNoName = currentNoName.getKey();
GeodeticPoint valueNoName = currentNoName.getValue();
// Comparison of each SensorPixel (for the key part and the value part)
if (TestUtils.sameSensorPixels(key, keyNoName, 1.e-3) &&
TestUtils.sameGeodeticPoints(value, valueNoName, 1.e-3)) {
// we found a match ...
found = true;
}
} // end iteration on mappingNoName
if (!found) { // the current (key,value) of the mapping was not found in the mappingNoName
Assert.assertTrue(found);
}
} // end on iteration on mapping
Assert.assertEquals(arraySensorToGroundMapping.getRuggedName(),arraySensorToGroundMappingNoName.getRuggedName());
Assert.assertEquals(arraySensorToGroundMapping.getSensorName(),arraySensorToGroundMappingNoName.getSensorName());;
}
@After
public void tearDown() {
measurements = null;
}
private InitGroundRefiningTest refiningTest;
private Observables measurements;
private Rugged rugged;
private String sensorName;
private int numberOfParameters;
private final int lineSampling = 1000;
private final int pixelSampling = 1000;
}
/* 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.adjustment;
import java.lang.reflect.Field;
import java.util.ArrayList;
import java.util.Collection;
import java.util.Iterator;
import java.util.List;
import java.util.Map;
import java.util.Map.Entry;
import java.util.Set;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresProblem;
import org.junit.After;
import org.junit.Assert;
import org.junit.Before;
import org.junit.Test;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping;
import org.orekit.rugged.adjustment.util.InitInterRefiningTest;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.SensorPixel;
public class InterSensorOptimizationProblemBuilderTest {
@Before
public void setUp() {
try {
refiningTest = new InitInterRefiningTest();
refiningTest.initRefiningTest();
ruggedList = refiningTest.getRuggedList();
earthConstraintWeight = 0.1;
measurements = refiningTest.generateNoisyPoints(lineSampling, pixelSampling, earthConstraintWeight, false);
numberOfParameters = refiningTest.getParameterToAdjust();
} catch (RuggedException re) {
Assert.fail(re.getLocalizedMessage());
}
}
@Test
public void testEstimateFreeParameters() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
AdjustmentContext adjustmentContext = new AdjustmentContext(ruggedList, measurements);
List<String> ruggedNameList = new ArrayList<String>();
for(Rugged rugged : ruggedList) {
ruggedNameList.add(rugged.getName());
}
final int maxIterations = 100;
final double convergenceThreshold = 1.e-7;
Optimum optimum = adjustmentContext.estimateFreeParameters(ruggedNameList, maxIterations, convergenceThreshold);
Assert.assertTrue(optimum.getIterations() < maxIterations);
// The default optimizer is a Gauss Newton.
// For Gauss Newton, the number of evaluations is equal to the number of iterations
Assert.assertTrue(optimum.getEvaluations() == optimum.getIterations());
final double expectedMaxValue = 1.924769e-03;
Assert.assertEquals(expectedMaxValue, optimum.getResiduals().getMaxValue(), 1.0e-6);
final double expectedRMS = 0.069302;
Assert.assertEquals(expectedRMS, optimum.getRMS(), 1.0e-6);
final double expectedCost = 3.597082e+00;
Assert.assertEquals(expectedCost, optimum.getCost(), 1.0e-6);
Assert.assertTrue(numberOfParameters == optimum.getPoint().getDimension());
final int sensorToSensorMappingSize = 1347;
Collection<SensorToSensorMapping> ssm = measurements.getInterMappings();
Iterator<SensorToSensorMapping> it = ssm.iterator();
while (it.hasNext()) {
SensorToSensorMapping ssmit = it.next();
Assert.assertTrue(sensorToSensorMappingSize == ssmit.getMapping().size());
}
Assert.assertTrue(sensorToSensorMappingSize*2 == optimum.getResiduals().getDimension());
}
@Test
public void testEarthConstraintPostponed() {
// Get the measurements as computed in other tests
Collection<SensorToSensorMapping> sensorToSensorMapping = measurements.getInterMappings();
int nbModels = measurements.getNbModels();
// Recompute the measurements in another way ... but that must be the same after all
Observables measurementsPostponed = refiningTest.generateNoisyPoints(lineSampling, pixelSampling, earthConstraintWeight, true);
Collection<SensorToSensorMapping> sensorToSensorMappingPostponed = measurementsPostponed.getInterMappings();
int nbModelsPostponed = measurementsPostponed.getNbModels();
// Compare the two collections of measurements
Assert.assertEquals(nbModels, nbModelsPostponed);
Assert.assertEquals(sensorToSensorMapping.size(), sensorToSensorMappingPostponed.size());
// There is only one item
SensorToSensorMapping arraySensorToSensorMapping = (SensorToSensorMapping) sensorToSensorMapping.toArray()[0];
SensorToSensorMapping arraySensorToSensorMappingPostponed = (SensorToSensorMapping) sensorToSensorMappingPostponed.toArray()[0];
List<Double> listBody = arraySensorToSensorMapping.getBodyDistances();
// Convert List<Double> to double[]
double[] arrayBody = listBody.stream().mapToDouble(Double::doubleValue).toArray(); //via method reference
// Explanations:
// get the Stream<Double> from the list
// map each double instance to its primitive value, resulting in a DoubleStream
// call toArray() to get the array.
// Other method: double[] arrayBody = listBody.stream().mapToDouble(d -> d).toArray(); //identity function, Java unboxes automatically to get the double value
List<Double> listBodyPostponed = arraySensorToSensorMappingPostponed.getBodyDistances();
double[] arrayBodyPostponed = listBodyPostponed.stream().mapToDouble(Double::doubleValue).toArray();
Assert.assertEquals(listBody.size(), listBodyPostponed.size());
Assert.assertArrayEquals(arrayBody, arrayBodyPostponed, 1.e-3);
List<Double> listLos = arraySensorToSensorMapping.getLosDistances();
double[] arrayLos = listLos.stream().mapToDouble(Double::doubleValue).toArray();
List<Double> listLosPostponed = arraySensorToSensorMappingPostponed.getLosDistances();
double[] arrayLosPostponed = listLosPostponed.stream().mapToDouble(Double::doubleValue).toArray();
Assert.assertEquals(listLos.size(), listLosPostponed.size());
Assert.assertArrayEquals(arrayLos, arrayLosPostponed, 1.e-6);
// Check if the two set are the same
Set<Entry<SensorPixel, SensorPixel>> mapping = arraySensorToSensorMapping.getMapping();
Set<Entry<SensorPixel, SensorPixel>> mappingPostponed = arraySensorToSensorMappingPostponed.getMapping();
Iterator<Entry<SensorPixel, SensorPixel>> itMapping = mapping.iterator();
while(itMapping.hasNext()) {
Entry<SensorPixel, SensorPixel> current = itMapping.next();
SensorPixel key = current.getKey();
SensorPixel value = current.getValue();
// Will search in mappingPostponed if we can find the (key,value) found in mapping
Boolean found = false;
Iterator<Entry<SensorPixel, SensorPixel>> itMappingPost = mappingPostponed.iterator();
while(itMappingPost.hasNext()) {
Entry<SensorPixel, SensorPixel> currentPost = itMappingPost.next();
SensorPixel keyPost = currentPost.getKey();
SensorPixel valuePost = currentPost.getValue();
// Comparison of each SensorPixel (for the key part and the value part)
if (TestUtils.sameSensorPixels(key, keyPost, 1.e-3) &&
TestUtils.sameSensorPixels(value, valuePost, 1.e-3)) {
// we found a match ...
found = true;
}
} // end iteration on mappingPostponed
if (!found) { // the current (key,value) of the mapping was not found in the mappingPostponed
Assert.assertTrue(found);
}
} // end on iteration on mapping
Assert.assertEquals(arraySensorToSensorMapping.getRuggedNameA(),arraySensorToSensorMappingPostponed.getRuggedNameA());
Assert.assertEquals(arraySensorToSensorMapping.getRuggedNameB(),arraySensorToSensorMappingPostponed.getRuggedNameB());;
Assert.assertEquals(arraySensorToSensorMapping.getSensorNameA(),arraySensorToSensorMappingPostponed.getSensorNameA());;
Assert.assertEquals(arraySensorToSensorMapping.getSensorNameB(),arraySensorToSensorMappingPostponed.getSensorNameB());
}
@Test
public void testDefaultRuggedNames() {
// In that case there are no body distance set at construction
// Generate intermapping with simple constructor of SensorToSensorMapping with Earth Constraint Weight given at construction
Observables measurementsWithWeight = refiningTest.generateSimpleInterMapping(lineSampling, pixelSampling, earthConstraintWeight, false);
Collection<SensorToSensorMapping> sensorToSensorMappingWithWeight = measurementsWithWeight.getInterMappings();
int nbModelsWithWeight = measurementsWithWeight.getNbModels();
// Generate intermapping with simple constructor of SensorToSensorMapping with Earth Constraint Weight given after construction
Observables measurementsWithoutWeight = refiningTest.generateSimpleInterMapping(lineSampling, pixelSampling, earthConstraintWeight, true);
Collection<SensorToSensorMapping> sensorToSensorMappingPostponed = measurementsWithoutWeight.getInterMappings();
int nbModelsPostponed = measurementsWithoutWeight.getNbModels();
// Compare the two collections of measurements
Assert.assertEquals(nbModelsWithWeight, nbModelsPostponed);
Assert.assertEquals(sensorToSensorMappingWithWeight.size(), sensorToSensorMappingPostponed.size());
// There is only one item
SensorToSensorMapping arraySensorToSensorMappingWithWeight = (SensorToSensorMapping) sensorToSensorMappingWithWeight.toArray()[0];
SensorToSensorMapping arraySensorToSensorMappingPostponed = (SensorToSensorMapping) sensorToSensorMappingPostponed.toArray()[0];
List<Double> listLosWithWeight = arraySensorToSensorMappingWithWeight.getLosDistances();
double[] arrayLosWithWeight = listLosWithWeight.stream().mapToDouble(Double::doubleValue).toArray();
List<Double> listLosPostponed = arraySensorToSensorMappingPostponed.getLosDistances();
double[] arrayLosPostponed = listLosPostponed.stream().mapToDouble(Double::doubleValue).toArray();
Assert.assertEquals(listLosWithWeight.size(), listLosPostponed.size());
Assert.assertArrayEquals(arrayLosWithWeight, arrayLosPostponed, 1.e-6);
// Check if the two set are the same
Set<Entry<SensorPixel, SensorPixel>> mappingWithWeight = arraySensorToSensorMappingWithWeight.getMapping();
Set<Entry<SensorPixel, SensorPixel>> mappingPostponed = arraySensorToSensorMappingPostponed.getMapping();
Iterator<Entry<SensorPixel, SensorPixel>> itMapping = mappingWithWeight.iterator();
while(itMapping.hasNext()) {
Entry<SensorPixel, SensorPixel> current = itMapping.next();
SensorPixel key = current.getKey();
SensorPixel value = current.getValue();
// Will search in mappingPostponed if we can find the (key,value) found in mapping
Boolean found = false;
Iterator<Entry<SensorPixel, SensorPixel>> itMappingPost = mappingPostponed.iterator();
while(itMappingPost.hasNext()) {
Entry<SensorPixel, SensorPixel> currentPost = itMappingPost.next();
SensorPixel keyPost = currentPost.getKey();
SensorPixel valuePost = currentPost.getValue();
// Comparison of each SensorPixel (for the key part and the value part)
if (TestUtils.sameSensorPixels(key, keyPost, 1.e-3) &&
TestUtils.sameSensorPixels(value, valuePost, 1.e-3)) {
// we found a match ...
found = true;
}
} // end iteration on mappingPostponed
if (!found) { // the current (key,value) of the mapping was not found in the mappingPostponed
Assert.assertTrue(found);
}
} // end on iteration on mapping
Assert.assertEquals(arraySensorToSensorMappingWithWeight.getRuggedNameA(),arraySensorToSensorMappingPostponed.getRuggedNameA());
Assert.assertEquals(arraySensorToSensorMappingWithWeight.getRuggedNameB(),arraySensorToSensorMappingPostponed.getRuggedNameB());;
Assert.assertEquals(arraySensorToSensorMappingWithWeight.getSensorNameA(),arraySensorToSensorMappingPostponed.getSensorNameA());;
Assert.assertEquals(arraySensorToSensorMappingWithWeight.getSensorNameB(),arraySensorToSensorMappingPostponed.getSensorNameB());
}
@Test
public void testNoReferenceMapping() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
try {
final int maxIterations = 120;
final double convergenceThreshold = 1.e-7;
final List<LineSensor> selectedSensors = new ArrayList<LineSensor>();
for (Rugged rugged : ruggedList) {
selectedSensors.addAll(rugged.getLineSensors());
}
final InterSensorsOptimizationProblemBuilder interSensorsOptimizationProblem =
new InterSensorsOptimizationProblemBuilder(selectedSensors, measurements, ruggedList);
Field sensorToSensorMapping = interSensorsOptimizationProblem.getClass().getDeclaredField("sensorToSensorMappings");
sensorToSensorMapping.setAccessible(true);
sensorToSensorMapping.set(interSensorsOptimizationProblem,new ArrayList<SensorToSensorMapping>());
interSensorsOptimizationProblem.build(maxIterations, convergenceThreshold);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.NO_REFERENCE_MAPPINGS,re.getSpecifier());
}
}
@Test
public void testInvalidRuggedNames() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
final int maxIterations = 120;
final double convergenceThreshold = 1.e-7;
final List<LineSensor> selectedSensors = new ArrayList<LineSensor>();
for (Rugged rugged : ruggedList) {
selectedSensors.addAll(rugged.getLineSensors());
}
final InterSensorsOptimizationProblemBuilder interSensorsOptimizationProblem =
new InterSensorsOptimizationProblemBuilder(selectedSensors, measurements, ruggedList);
Field ruggedMapField = interSensorsOptimizationProblem.getClass().getDeclaredField("ruggedMap");
ruggedMapField.setAccessible(true);
@SuppressWarnings("unchecked")
Map<String,Rugged> ruggedMap = (Map<String,Rugged>) ruggedMapField.get(interSensorsOptimizationProblem);
// Set first RuggedB to null to get the right exception ...
try {
ruggedMap.put("RuggedB",null);
ruggedMapField.set(interSensorsOptimizationProblem,ruggedMap);
final LeastSquareAdjuster adjuster = new LeastSquareAdjuster(OptimizerId.GAUSS_NEWTON_QR);
LeastSquaresProblem theProblem = interSensorsOptimizationProblem.build(maxIterations, convergenceThreshold);
adjuster.optimize(theProblem);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getSpecifier());
}
// Then set RuggedA to null to get the right exception ...
try {
ruggedMap.put("RuggedA",null);
ruggedMapField.set(interSensorsOptimizationProblem,ruggedMap);
final LeastSquareAdjuster adjuster = new LeastSquareAdjuster(OptimizerId.GAUSS_NEWTON_QR);
LeastSquaresProblem theProblem = interSensorsOptimizationProblem.build(maxIterations, convergenceThreshold);
adjuster.optimize(theProblem);
Assert.fail("An exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.INVALID_RUGGED_NAME,re.getSpecifier());
}
}
@After
public void tearDown() {
measurements = null;
ruggedList = null;
}
private InitInterRefiningTest refiningTest;
private Observables measurements;
private List<Rugged> ruggedList;
private int numberOfParameters;
private double earthConstraintWeight;
private final int lineSampling = 1000;
private final int pixelSampling = 1000;
}
package org.orekit.rugged.adjustment;
import org.junit.Assert;
import java.lang.reflect.Field;
import org.junit.Test;
public class LeastSquareAdjusterTest {
@Test
public void testLeastSquareAdjuster() throws NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
final LeastSquareAdjuster adjusterWithOptimizer = new LeastSquareAdjuster(OptimizerId.GAUSS_NEWTON_QR);
final LeastSquareAdjuster adjusterWithDefaultOptimizer = new LeastSquareAdjuster();
Field optimizerIdWithOptimizer = adjusterWithOptimizer.getClass().getDeclaredField("optimizerID");
optimizerIdWithOptimizer.setAccessible(true);
OptimizerId getOptimizerIdWithOptimizer = (OptimizerId) optimizerIdWithOptimizer.get(adjusterWithOptimizer);
Field optimizerIdWithDefaultOptimizer = adjusterWithDefaultOptimizer.getClass().getDeclaredField("optimizerID");
optimizerIdWithDefaultOptimizer.setAccessible(true);
OptimizerId getOptimizerIdWithDefaultOptimizer = (OptimizerId) optimizerIdWithDefaultOptimizer.get(adjusterWithDefaultOptimizer);
Assert.assertTrue(getOptimizerIdWithDefaultOptimizer == getOptimizerIdWithOptimizer);
}
}
package org.orekit.rugged.adjustment.util;
import java.io.File;
import java.net.URISyntaxException;
import java.util.List;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.random.GaussianRandomGenerator;
import org.hipparchus.random.UncorrelatedRandomVectorGenerator;
import org.hipparchus.random.Well19937a;
import org.hipparchus.util.FastMath;
import org.junit.Assert;
import org.orekit.bodies.BodyShape;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.orbits.Orbit;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.measurements.SensorToGroundMapping;
import org.orekit.rugged.api.AlgorithmId;
import org.orekit.rugged.api.BodyRotatingFrameId;
import org.orekit.rugged.api.EllipsoidId;
import org.orekit.rugged.api.InertialFrameId;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.api.RuggedBuilder;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.time.AbsoluteDate;
import org.orekit.utils.AngularDerivativesFilter;
import org.orekit.utils.CartesianDerivativesFilter;
import org.orekit.utils.Constants;
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.utils.TimeStampedPVCoordinates;
/** Initialization for ground refining (Ground Control Points GCP study) Junit tests.
* @author Guylaine Prat
*/
public class InitGroundRefiningTest {
/** Pleiades viewing model */
private PleiadesViewingModel pleiadesViewingModel;
/** Line sensor */
private LineSensor lineSensor;
/** Rugged's instance */
private Rugged rugged;
/** Number of parameters to adjust */
private int parameterToAdjust;
// Part of the name of parameter drivers
static final String rollSuffix = "_roll";
static final String pitchSuffix = "_pitch";
static final String factorName = "factor";
// Default values for disruption to apply to roll (deg), pitch (deg) and factor
static final double defaultRollDisruption = 0.004;
static final double defaultPitchDisruption = 0.0008;
static final double defaultFactorDisruption = 1.000000001;
/**
* Initialize ground refining tests with default values for disruptions on sensors characteristics
*/
public void initGroundRefiningTest() {
initGroundRefiningTest(defaultRollDisruption, defaultPitchDisruption, defaultFactorDisruption);
}
/** Initialize ground refining tests with disruption on sensors characteristics
* @param rollDisruption disruption to apply to roll angle for sensor (deg)
* @param pitchDisruption disruption to apply to pitch angle for sensor (deg)
* @param factorDisruption disruption to apply to homothety factor for sensor
*/
public void initGroundRefiningTest(double rollDisruption, double pitchDisruption, double factorDisruption) {
try {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
// Initialize refining context
// ---------------------------
final String sensorName = "line";
final double incidenceAngle = -5.0;
final String date = "2016-01-01T11:59:50.0";
this.pleiadesViewingModel = new PleiadesViewingModel(sensorName, incidenceAngle, date);
PleiadesOrbitModel orbitmodel = new PleiadesOrbitModel();
// Sensor's definition: creation of Pleiades viewing model
// --------------------------------------------------------
// Create Pleiades Viewing Model
final AbsoluteDate minDate = pleiadesViewingModel.getMinDate();
final AbsoluteDate maxDate = pleiadesViewingModel.getMaxDate();
final AbsoluteDate refDate = pleiadesViewingModel.getDatationReference();
this.lineSensor = pleiadesViewingModel.getLineSensor();
// ----Satellite position, velocity and attitude: create orbit model
BodyShape earth = TestUtils.createEarth();
Orbit orbit = orbitmodel.createOrbit(Constants.EIGEN5C_EARTH_MU, refDate);
// ----If no LOF Transform Attitude Provider is Nadir Pointing Yaw Compensation
final double [] rollPoly = {0.0,0.0,0.0};
final double[] pitchPoly = {0.025,0.0};
final double[] yawPoly = {0.0,0.0,0.0};
orbitmodel.setLOFTransform(rollPoly, pitchPoly, yawPoly, minDate);
// ----Satellite attitude
List<TimeStampedAngularCoordinates> satelliteQList = orbitmodel.orbitToQ(orbit, earth, minDate.shiftedBy(-0.0), maxDate.shiftedBy(+0.0), 0.25);
final int nbQPoints = 2;
// ----Position and velocities
List<TimeStampedPVCoordinates> satellitePVListA = orbitmodel.orbitToPV(orbit, earth, minDate.shiftedBy(-0.0), maxDate.shiftedBy(+0.0), 0.25);
final int nbPVPoints = 8;
// Rugged initialization
// ---------------------
RuggedBuilder ruggedBuilder = new RuggedBuilder();
ruggedBuilder.addLineSensor(lineSensor);
ruggedBuilder.setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
ruggedBuilder.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
ruggedBuilder.setTimeSpan(minDate,maxDate, 0.001, 5.0);
ruggedBuilder.setTrajectory(InertialFrameId.EME2000, satellitePVListA, nbPVPoints,
CartesianDerivativesFilter.USE_PV, satelliteQList,
nbQPoints, AngularDerivativesFilter.USE_R);
ruggedBuilder.setLightTimeCorrection(false);
ruggedBuilder.setAberrationOfLightCorrection(false);
ruggedBuilder.setName("Rugged");
this.rugged = ruggedBuilder.build();
// Select parameters to adjust
// ---------------------------
RefiningParametersDriver.setSelectedRoll(rugged, sensorName);
RefiningParametersDriver.setSelectedPitch(rugged, sensorName);
this.parameterToAdjust = 2;
// Initialize disruptions:
// -----------------------
// introduce rotations around instrument axes (roll and pitch angles, scale factor)
// apply disruptions on physical model
RefiningParametersDriver.applyDisruptionsRoll(rugged, sensorName, FastMath.toRadians(rollDisruption));
RefiningParametersDriver.applyDisruptionsPitch(rugged, sensorName, FastMath.toRadians(pitchDisruption));
RefiningParametersDriver.applyDisruptionsFactor(rugged, sensorName, factorDisruption);
} catch (OrekitException oe) {
Assert.fail(oe.getLocalizedMessage());
} catch (URISyntaxException use) {
Assert.fail(use.getLocalizedMessage());
}
}
/**
* Get the Rugged instance
* @return rugged instance
*/
public Rugged getRugged(){
return this.rugged;
}
/** Generate noisy measurements (sensor to ground mapping)
* @param lineSampling line sampling
* @param pixelSampling pixel sampling
* @param flag to tell if the Rugged name used is the default one (true) or not (false)
*/
public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, boolean defaultRuggedName) {
// Generate reference mapping
SensorToGroundMapping groundMapping;
if (!defaultRuggedName) {
groundMapping = new SensorToGroundMapping(rugged.getName(), lineSensor.getName());
} else {
// The rugged name used in this test is the same as the dafult one in SensorToGroundMapping
groundMapping = new SensorToGroundMapping(lineSensor.getName());
}
// Observable which contains sensor to ground mapping (one model)
Observables observable = new Observables(1);
// Estimate latitude and longitude errors (rad)
final int pixelMiddle= lineSensor.getNbPixels() / 2;
final int lineMiddle = (int) FastMath.floor(pixelMiddle);
final AbsoluteDate dateMiddle = lineSensor.getDate(lineMiddle);
final GeodeticPoint gp_pix0 = rugged.directLocation(dateMiddle, lineSensor.getPosition(), lineSensor.getLOS(dateMiddle, pixelMiddle));
final AbsoluteDate date1 = lineSensor.getDate(lineMiddle + 1);
final GeodeticPoint gp_pix1 = rugged.directLocation(date1, lineSensor.getPosition(), lineSensor.getLOS(date1, pixelMiddle + 1));
final double latitudeErr = FastMath.abs(gp_pix0.getLatitude() - gp_pix1.getLatitude());
final double longitudeErr = FastMath.abs(gp_pix0.getLongitude() - gp_pix1.getLongitude());
// Generation noisy measurements
// distribution: gaussian(0), vector dimension: 3 (for latitude, longitude and altitude)
// Mean latitude, longitude and altitude
final double[] mean = {5.0,5.0,5.0};
// Standard deviation latitude, longitude and altitude
final double[] std = {0.1,0.1,0.1};
final double latErrorMean = mean[0] * latitudeErr;
final double lonErrorMean = mean[1] * longitudeErr;
final double latErrorStd = std[0] * latitudeErr;
final double lonErrorStd = std[1] * longitudeErr;
// Gaussian random generator
// Build a null mean random uncorrelated vector generator with standard deviation corresponding to the estimated error on ground
final double meanGenerator[] = {latErrorMean, lonErrorMean, mean[2]};
final double stdGenerator[] = {latErrorStd, lonErrorStd, std[2]};
// seed has been fixed for tests purpose
final GaussianRandomGenerator rng = new GaussianRandomGenerator(new Well19937a(0xefac03d9be4d24b9l));
final UncorrelatedRandomVectorGenerator rvg = new UncorrelatedRandomVectorGenerator(meanGenerator, stdGenerator, rng);
for (double line = 0; line < pleiadesViewingModel.getDimension(); line += lineSampling) {
final AbsoluteDate date = lineSensor.getDate(line);
for (int pixel = 0; pixel < lineSensor.getNbPixels(); pixel += pixelSampling) {
// Components of generated vector follow (independent) Gaussian distribution
final Vector3D vecRandom = new Vector3D(rvg.nextVector());
final GeodeticPoint gp2 = rugged.directLocation(date, lineSensor.getPosition(),
lineSensor.getLOS(date, pixel));
final GeodeticPoint gpNoisy = new GeodeticPoint(gp2.getLatitude() + vecRandom.getX(),
gp2.getLongitude() + vecRandom.getY(),
gp2.getAltitude() + vecRandom.getZ());
groundMapping.addMapping(new SensorPixel(line, pixel), gpNoisy);
}
}
observable.addGroundMapping(groundMapping);
return observable;
}
/** Get the number of parameters to adjust
* @return number of parameters to adjust
*/
public int getParameterToAdjust() {
return parameterToAdjust;
}
}
package org.orekit.rugged.adjustment.util;
import java.io.File;
import java.lang.reflect.InvocationTargetException;
import java.net.URISyntaxException;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import org.hipparchus.analysis.differentiation.DerivativeStructure;
import org.hipparchus.analysis.differentiation.Gradient;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.random.GaussianRandomGenerator;
import org.hipparchus.random.UncorrelatedRandomVectorGenerator;
import org.hipparchus.random.Well19937a;
import org.hipparchus.util.FastMath;
import org.junit.After;
import org.junit.Assert;
import org.orekit.bodies.BodyShape;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.orbits.Orbit;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.adjustment.InterSensorsOptimizationProblemBuilder;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.measurements.SensorToSensorMapping;
import org.orekit.rugged.api.AlgorithmId;
import org.orekit.rugged.api.BodyRotatingFrameId;
import org.orekit.rugged.api.EllipsoidId;
import org.orekit.rugged.api.InertialFrameId;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.api.RuggedBuilder;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.rugged.utils.DerivativeGenerator;
import org.orekit.rugged.utils.SpacecraftToObservedBody;
import org.orekit.time.AbsoluteDate;
import org.orekit.utils.AngularDerivativesFilter;
import org.orekit.utils.CartesianDerivativesFilter;
import org.orekit.utils.Constants;
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.utils.TimeStampedPVCoordinates;
/** Initialization for inter sensor refining Junit tests.
* @author Guylaine Prat
*/
public class InitInterRefiningTest {
/** Pleiades viewing model A */
private PleiadesViewingModel pleiadesViewingModelA;
/** Pleiades viewing model B */
private PleiadesViewingModel pleiadesViewingModelB;
/** Line sensor A */
private LineSensor lineSensorA;
/** Line sensor B */
private LineSensor lineSensorB;
/** RuggedA's instance */
private Rugged ruggedA;
/** RuggedB's instance */
private Rugged ruggedB;
/** Number of parameters to adjust */
private int parameterToAdjust;
// Part of the name of parameter drivers
static final String rollSuffix = "_roll";
static final String pitchSuffix = "_pitch";
static final String factorName = "factor";
// Default values for disruption to apply to roll (deg), pitch (deg) and factor
static final double defaultRollDisruptionA = 0.004;
static final double defaultPitchDisruptionA = 0.0008;
static final double defaultFactorDisruptionA = 1.000000001;
static final double defaultRollDisruptionB = -0.004;
static final double defaultPitchDisruptionB = 0.0008;
/**
* Initialize refining tests with default values for disruptions on sensors characteristics
*/
public void initRefiningTest() {
initRefiningTest(defaultRollDisruptionA, defaultPitchDisruptionA, defaultFactorDisruptionA,
defaultRollDisruptionB, defaultPitchDisruptionB);
}
/** Initialize refining tests with disruption on sensors characteristics
* @param rollDisruptionA disruption to apply to roll angle for sensor A (deg)
* @param pitchDisruptionA disruption to apply to pitch angle for sensor A (deg)
* @param factorDisruptionA disruption to apply to homothety factor for sensor A
* @param rollDisruptionB disruption to apply to roll angle for sensor B (deg)
* @param pitchDisruptionB disruption to apply to pitch angle for sensor B (deg)
*/
public void initRefiningTest(double rollDisruptionA, double pitchDisruptionA, double factorDisruptionA,
double rollDisruptionB, double pitchDisruptionB) {
try {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
// Initialize refining context
// ---------------------------
final String sensorNameA = "SensorA";
final double incidenceAngleA = -5.0;
final String dateA = "2016-01-01T11:59:50.0";
this.pleiadesViewingModelA = new PleiadesViewingModel(sensorNameA, incidenceAngleA, dateA);
final String sensorNameB = "SensorB";
final double incidenceAngleB = 0.0;
final String dateB = "2016-01-01T12:02:50.0";
this.pleiadesViewingModelB = new PleiadesViewingModel(sensorNameB, incidenceAngleB, dateB);
PleiadesOrbitModel orbitmodelA = new PleiadesOrbitModel();
PleiadesOrbitModel orbitmodelB = new PleiadesOrbitModel();
// Sensors's definition: creation of 2 Pleiades viewing models
// -----------------------------------------------------------
// 1/- Create First Pleiades Viewing Model A
final AbsoluteDate minDateA = pleiadesViewingModelA.getMinDate();
final AbsoluteDate maxDateA = pleiadesViewingModelA.getMaxDate();
final AbsoluteDate refDateA = pleiadesViewingModelA.getDatationReference();
this.lineSensorA = pleiadesViewingModelA.getLineSensor();
// ----Satellite position, velocity and attitude: create orbit model A
BodyShape earthA = TestUtils.createEarth();
Orbit orbitA = orbitmodelA.createOrbit(Constants.EIGEN5C_EARTH_MU, refDateA);
// ----If no LOF Transform Attitude Provider is Nadir Pointing Yaw Compensation
final double [] rollPoly = {0.0,0.0,0.0};
final double[] pitchPoly = {0.025,0.0};
final double[] yawPoly = {0.0,0.0,0.0};
orbitmodelA.setLOFTransform(rollPoly, pitchPoly, yawPoly, minDateA);
// ----Satellite attitude
List<TimeStampedAngularCoordinates> satelliteQListA = orbitmodelA.orbitToQ(orbitA, earthA, minDateA.shiftedBy(-0.0), maxDateA.shiftedBy(+0.0), 0.25);
final int nbQPoints = 2;
// ----Position and velocities
List<TimeStampedPVCoordinates> satellitePVListA = orbitmodelA.orbitToPV(orbitA, earthA, minDateA.shiftedBy(-0.0), maxDateA.shiftedBy(+0.0), 0.25);
final int nbPVPoints = 8;
// Rugged A initialization
// ---------------------
RuggedBuilder ruggedBuilderA = new RuggedBuilder();
ruggedBuilderA.addLineSensor(lineSensorA);
ruggedBuilderA.setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
ruggedBuilderA.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
ruggedBuilderA.setTimeSpan(minDateA,maxDateA, 0.001, 5.0);
ruggedBuilderA.setTrajectory(InertialFrameId.EME2000, satellitePVListA, nbPVPoints,
CartesianDerivativesFilter.USE_PV, satelliteQListA,
nbQPoints, AngularDerivativesFilter.USE_R);
ruggedBuilderA.setLightTimeCorrection(false);
ruggedBuilderA.setAberrationOfLightCorrection(false);
ruggedBuilderA.setName("RuggedA");
this.ruggedA = ruggedBuilderA.build();
// 2/- Create Second Pleiades Viewing Model
final AbsoluteDate minDateB = pleiadesViewingModelB.getMinDate();
final AbsoluteDate maxDateB = pleiadesViewingModelB.getMaxDate();
final AbsoluteDate refDateB = pleiadesViewingModelB.getDatationReference();
this.lineSensorB = pleiadesViewingModelB.getLineSensor();
// ----Satellite position, velocity and attitude: create orbit model B
BodyShape earthB = TestUtils.createEarth();
Orbit orbitB = orbitmodelB.createOrbit(Constants.EIGEN5C_EARTH_MU, refDateB);
// ----Satellite attitude
List<TimeStampedAngularCoordinates> satelliteQListB = orbitmodelB.orbitToQ(orbitB, earthB, minDateB.shiftedBy(-0.0), maxDateB.shiftedBy(+0.0), 0.25);
// ----Position and velocities
List<TimeStampedPVCoordinates> satellitePVListB = orbitmodelB.orbitToPV(orbitB, earthB, minDateB.shiftedBy(-0.0), maxDateB.shiftedBy(+0.0), 0.25);
// Rugged B initialization
// ---------------------
RuggedBuilder ruggedBuilderB = new RuggedBuilder();
ruggedBuilderB.addLineSensor(lineSensorB);
ruggedBuilderB.setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID);
ruggedBuilderB.setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF);
ruggedBuilderB.setTimeSpan(minDateB,maxDateB, 0.001, 5.0);
ruggedBuilderB.setTrajectory(InertialFrameId.EME2000, satellitePVListB, nbPVPoints,
CartesianDerivativesFilter.USE_PV, satelliteQListB,
nbQPoints, AngularDerivativesFilter.USE_R);
ruggedBuilderB.setLightTimeCorrection(false);
ruggedBuilderB.setAberrationOfLightCorrection(false);
ruggedBuilderB.setName("RuggedB");
this.ruggedB = ruggedBuilderB.build();
// Select parameters to adjust
// ---------------------------
RefiningParametersDriver.setSelectedRoll(ruggedA, sensorNameA);
RefiningParametersDriver.setSelectedPitch(ruggedA, sensorNameA);
RefiningParametersDriver.setSelectedRoll(ruggedB, sensorNameB);
RefiningParametersDriver.setSelectedPitch(ruggedB, sensorNameB);
this.parameterToAdjust = 4;
// Initialize disruptions:
// -----------------------
// introduce rotations around instrument axes (roll and pitch angles, scale factor)
// apply disruptions on physical model (acquisition A)
RefiningParametersDriver.applyDisruptionsRoll(ruggedA, sensorNameA, FastMath.toRadians(rollDisruptionA));
RefiningParametersDriver.applyDisruptionsPitch(ruggedA, sensorNameA, FastMath.toRadians(pitchDisruptionA));
RefiningParametersDriver.applyDisruptionsFactor(ruggedA, sensorNameA, factorDisruptionA);
// apply disruptions on physical model (acquisition B)
RefiningParametersDriver.applyDisruptionsRoll(ruggedB, sensorNameB, FastMath.toRadians(rollDisruptionB));
RefiningParametersDriver.applyDisruptionsPitch(ruggedB, sensorNameB, FastMath.toRadians(pitchDisruptionB));
} catch (OrekitException oe) {
Assert.fail(oe.getLocalizedMessage());
} catch (URISyntaxException use) {
Assert.fail(use.getLocalizedMessage());
}
}
/**
* Get the list of Rugged instances
* @return rugged instances as list
*/
public List<Rugged> getRuggedList(){
List<Rugged> ruggedList = Arrays.asList(ruggedA, ruggedB);
return ruggedList;
}
/** Compute the distances between LOS of two real pixels (one from sensor A and one from sensor B)
* @param realPixelA real pixel from sensor A
* @param realPixelB real pixel from sensor B
* @return the distances of two real pixels computed between LOS and to the ground
*/
public double[] computeDistancesBetweenLOS(final SensorPixel realPixelA, final SensorPixel realPixelB) {
final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody();
final AbsoluteDate realDateA = lineSensorA.getDate(realPixelA.getLineNumber());
final AbsoluteDate realDateB = lineSensorB.getDate(realPixelB.getLineNumber());
final double[] distanceLOSB = ruggedB.distanceBetweenLOS(
lineSensorA, realDateA, realPixelA.getPixelNumber(),
scToBodyA,
lineSensorB, realDateB, realPixelB.getPixelNumber());
return distanceLOSB;
}
/** Compute the distances with derivatives between LOS of two real pixels (one from sensor A and one from sensor B)
* @param realPixelA real pixel from sensor A
* @param realPixelB real pixel from sensor B
* @return the distances of two real pixels computed between LOS and to the ground
* @deprecated as of 2.2, replaced by {@link #computeDistancesBetweenLOSGradient(SensorPixel, SensorPixel, double, double)}
*/
public DerivativeStructure[] computeDistancesBetweenLOSDerivatives(final SensorPixel realPixelA, final SensorPixel realPixelB,
final double losDistance, final double earthDistance)
throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException {
final Gradient[] gradient = computeDistancesBetweenLOSGradient(realPixelA, realPixelB, losDistance, earthDistance);
final DerivativeStructure[] ds = new DerivativeStructure[gradient.length];
for (int i = 0; i < gradient.length; ++i) {
ds[i] = gradient[i].toDerivativeStructure();
}
return ds;
}
/** Compute the distances with derivatives between LOS of two real pixels (one from sensor A and one from sensor B)
* @param realPixelA real pixel from sensor A
* @param realPixelB real pixel from sensor B
* @return the distances of two real pixels computed between LOS and to the ground
* @since 2.2
*/
public Gradient[] computeDistancesBetweenLOSGradient(final SensorPixel realPixelA, final SensorPixel realPixelB,
final double losDistance, final double earthDistance)
throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException {
final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody();
final AbsoluteDate realDateA = lineSensorA.getDate(realPixelA.getLineNumber());
final AbsoluteDate realDateB = lineSensorB.getDate(realPixelB.getLineNumber());
final List<LineSensor> sensors = new ArrayList<LineSensor>();
sensors.addAll(ruggedA.getLineSensors());
sensors.addAll(ruggedB.getLineSensors());
final List<Rugged> ruggedList = new ArrayList<Rugged>();
ruggedList.add(ruggedA);
ruggedList.add(ruggedB);
// prepare generator
final Observables measurements = new Observables(2);
SensorToSensorMapping interMapping = new SensorToSensorMapping(lineSensorA.getName(), ruggedA.getName(), lineSensorB.getName(), ruggedB.getName());
interMapping.addMapping(realPixelA, realPixelB, losDistance, earthDistance);
measurements.addInterMapping(interMapping);
InterSensorsOptimizationProblemBuilder optimizationPbBuilder = new InterSensorsOptimizationProblemBuilder(sensors, measurements, ruggedList);
java.lang.reflect.Method createGenerator = InterSensorsOptimizationProblemBuilder.class.getSuperclass().getDeclaredMethod("createGenerator", List.class);
createGenerator.setAccessible(true);
List<LineSensor> listLineSensor = new ArrayList<LineSensor>();
listLineSensor.addAll(ruggedA.getLineSensors());
listLineSensor.addAll(ruggedB.getLineSensors());
@SuppressWarnings("unchecked")
DerivativeGenerator<Gradient> generator = (DerivativeGenerator<Gradient>) createGenerator.invoke(optimizationPbBuilder, listLineSensor);
return ruggedB.distanceBetweenLOSderivatives(lineSensorA, realDateA, realPixelA.getPixelNumber(),
scToBodyA,
lineSensorB, realDateB, realPixelB.getPixelNumber(),
generator);
}
/** Generate noisy measurements (sensor to sensor mapping)
* @param lineSampling line sampling
* @param pixelSampling pixel sampling
* @param earthConstraintWeight the earth constrint weight
* @param earthConstraintPostponed flag to tell if the earth constraint weight is set at construction (false) or after (true) - For JUnit coverage purpose
*/
public Observables generateNoisyPoints(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) {
// Outliers control
final double outlierValue = 1.e+2;
// Generate measurements with constraints on Earth distance and outliers control
// Generate reference mapping, with Earth distance constraints.
// Weighting will be applied as follow :
// (1-earthConstraintWeight) for losDistance weighting
// earthConstraintWeight for earthDistance weighting
SensorToSensorMapping interMapping;
if (! earthConstraintPostponed) {
interMapping = new SensorToSensorMapping(lineSensorA.getName(), ruggedA.getName(),
lineSensorB.getName(), ruggedB.getName(),
earthConstraintWeight);
} else { // used for JUnit coverage purpose
interMapping = new SensorToSensorMapping(lineSensorA.getName(), ruggedA.getName(),
lineSensorB.getName(), ruggedB.getName());
// set the earthConstraintWeight after construction
interMapping.setBodyConstraintWeight(earthConstraintWeight);
}
// Observables which contains sensor to sensor mapping
Observables observables = new Observables(2);
// Generation noisy measurements
// distribution: gaussian(0), vector dimension: 2
final double meanA[] = { 5.0, 5.0 };
final double stdA[] = { 0.1, 0.1 };
final double meanB[] = { 0.0, 0.0 };
final double stdB[] = { 0.1, 0.1 };
// Seed has been fixed for tests purpose
final GaussianRandomGenerator rngA = new GaussianRandomGenerator(new Well19937a(0xefac03d9be4d24b9l));
final UncorrelatedRandomVectorGenerator rvgA = new UncorrelatedRandomVectorGenerator(meanA, stdA, rngA);
// Seed has been fixed for tests purpose
final GaussianRandomGenerator rngB = new GaussianRandomGenerator(new Well19937a(0xdf1c03d9be0b34b9l));
final UncorrelatedRandomVectorGenerator rvgB = new UncorrelatedRandomVectorGenerator(meanB, stdB, rngB);
// Search the sensor pixel seeing point
final int minLine = 0;
final int maxLine = pleiadesViewingModelB.getDimension() - 1;
final String sensorNameB = lineSensorB.getName();
for (double line = 0; line < pleiadesViewingModelA.getDimension(); line += lineSampling) {
final AbsoluteDate dateA = lineSensorA.getDate(line);
for (double pixelA = 0; pixelA < lineSensorA.getNbPixels(); pixelA += pixelSampling) {
final GeodeticPoint gpA = ruggedA.directLocation(dateA, lineSensorA.getPosition(),
lineSensorA.getLOS(dateA, pixelA));
final SensorPixel sensorPixelB = ruggedB.inverseLocation(sensorNameB, gpA, minLine, maxLine);
// We need to test if the sensor pixel is found in the prescribed lines
// otherwise the sensor pixel is null
if (sensorPixelB != null) {
final AbsoluteDate dateB = lineSensorB.getDate(sensorPixelB.getLineNumber());
final double pixelB = sensorPixelB.getPixelNumber();
// Get spacecraft to body transform of Rugged instance A
final SpacecraftToObservedBody scToBodyA = ruggedA.getScToBody();
final GeodeticPoint gpB = ruggedB.directLocation(dateB, lineSensorB.getPosition(),
lineSensorB.getLOS(dateB, pixelB));
final double geoDistance = computeDistanceInMeter(gpA, gpB);
// Create the inter mapping if distance is below outlier value
if (geoDistance < outlierValue) {
final double[] vecRandomA = rvgA.nextVector();
final double[] vecRandomB = rvgB.nextVector();
final SensorPixel realPixelA = new SensorPixel(line + vecRandomA[0], pixelA + vecRandomA[1]);
final SensorPixel realPixelB = new SensorPixel(sensorPixelB.getLineNumber() + vecRandomB[0],
sensorPixelB.getPixelNumber() + vecRandomB[1]);
final AbsoluteDate realDateA = lineSensorA.getDate(realPixelA.getLineNumber());
final AbsoluteDate realDateB = lineSensorB.getDate(realPixelB.getLineNumber());
final double[] distanceLOSB = ruggedB.distanceBetweenLOS(lineSensorA, realDateA, realPixelA.getPixelNumber(), scToBodyA,
lineSensorB, realDateB, realPixelB.getPixelNumber());
final Double losDistance = 0.0;
final Double earthDistance = distanceLOSB[1];
interMapping.addMapping(realPixelA, realPixelB, losDistance, earthDistance);
} // end test if geoDistance < outlierValue
} // end test if sensorPixelB != null
} // end loop on pixel of sensorA
} // end loop on line of sensorA
observables.addInterMapping(interMapping);
return observables;
}
/** Generate simple noisy measurements (sensor to sensor mapping)
* @param lineSampling line sampling
* @param pixelSampling pixel sampling
* @param earthConstraintWeight the earth constrint weight
* @param earthConstraintPostponed flag to tell if the earth constraint weight is set at construction (false) or after (true) - For JUnit coverage purpose
*/
public Observables generateSimpleInterMapping(final int lineSampling, final int pixelSampling, final double earthConstraintWeight, final boolean earthConstraintPostponed) {
// Outliers control
final double outlierValue = 1.e+2;
// Generate measurements with constraints on Earth distance and outliers control
// Generate reference mapping, with Earth distance constraints.
// Weighting will be applied as follow :
// (1-earthConstraintWeight) for losDistance weighting
// earthConstraintWeight for earthDistance weighting
SensorToSensorMapping interMapping;
if (! earthConstraintPostponed) {
interMapping = new SensorToSensorMapping(lineSensorA.getName(), lineSensorB.getName(), earthConstraintWeight);
} else { // used for JUnit coverage purpose
interMapping = new SensorToSensorMapping(lineSensorA.getName(), lineSensorB.getName());
// set the earthConstraintWeight after construction
interMapping.setBodyConstraintWeight(earthConstraintWeight);
}
// Observables which contains sensor to sensor mapping
Observables observables = new Observables(2);
// Generation noisy measurements
// distribution: gaussian(0), vector dimension: 2
final double meanA[] = { 5.0, 5.0 };
final double stdA[] = { 0.1, 0.1 };
final double meanB[] = { 0.0, 0.0 };
final double stdB[] = { 0.1, 0.1 };
// Seed has been fixed for tests purpose
final GaussianRandomGenerator rngA = new GaussianRandomGenerator(new Well19937a(0xefac03d9be4d24b9l));
final UncorrelatedRandomVectorGenerator rvgA = new UncorrelatedRandomVectorGenerator(meanA, stdA, rngA);
// Seed has been fixed for tests purpose
final GaussianRandomGenerator rngB = new GaussianRandomGenerator(new Well19937a(0xdf1c03d9be0b34b9l));
final UncorrelatedRandomVectorGenerator rvgB = new UncorrelatedRandomVectorGenerator(meanB, stdB, rngB);
// Search the sensor pixel seeing point
final int minLine = 0;
final int maxLine = pleiadesViewingModelB.getDimension() - 1;
final String sensorNameB = lineSensorB.getName();
for (double line = 0; line < pleiadesViewingModelA.getDimension(); line += lineSampling) {
final AbsoluteDate dateA = lineSensorA.getDate(line);
for (double pixelA = 0; pixelA < lineSensorA.getNbPixels(); pixelA += pixelSampling) {
final GeodeticPoint gpA = ruggedA.directLocation(dateA, lineSensorA.getPosition(),
lineSensorA.getLOS(dateA, pixelA));
final SensorPixel sensorPixelB = ruggedB.inverseLocation(sensorNameB, gpA, minLine, maxLine);
// We need to test if the sensor pixel is found in the prescribed lines
// otherwise the sensor pixel is null
if (sensorPixelB != null) {
final AbsoluteDate dateB = lineSensorB.getDate(sensorPixelB.getLineNumber());
final double pixelB = sensorPixelB.getPixelNumber();
final GeodeticPoint gpB = ruggedB.directLocation(dateB, lineSensorB.getPosition(),
lineSensorB.getLOS(dateB, pixelB));
final double geoDistance = computeDistanceInMeter(gpA, gpB);
// Create the inter mapping if distance is below outlier value
if (geoDistance < outlierValue) {
final double[] vecRandomA = rvgA.nextVector();
final double[] vecRandomB = rvgB.nextVector();
final SensorPixel realPixelA = new SensorPixel(line + vecRandomA[0], pixelA + vecRandomA[1]);
final SensorPixel realPixelB = new SensorPixel(sensorPixelB.getLineNumber() + vecRandomB[0],
sensorPixelB.getPixelNumber() + vecRandomB[1]);
// dummy value for JUnit test purpose
final Double losDistance = FastMath.abs(vecRandomA[0]);
interMapping.addMapping(realPixelA, realPixelB, losDistance);
} // end test if geoDistance < outlierValue
} // end test if sensorPixelB != null
} // end loop on pixel of sensorA
} // end loop on line of sensorA
observables.addInterMapping(interMapping);
return observables;
}
/** Compute a geodetic distance in meters between two geodetic points.
* @param geoPoint1 first geodetic point (rad)
* @param geoPoint2 second geodetic point (rad)
* @return distance in meters
*/
private static double computeDistanceInMeter(final GeodeticPoint geoPoint1, final GeodeticPoint geoPoint2) {
// get vectors on unit sphere from angular coordinates
final Vector3D p1 = new Vector3D(geoPoint1.getLatitude(), geoPoint1.getLongitude());
final Vector3D p2 = new Vector3D(geoPoint2.getLatitude(), geoPoint2.getLongitude());
return Constants.WGS84_EARTH_EQUATORIAL_RADIUS * Vector3D.angle(p1, p2);
}
/** Get the number of parameters to adjust
* @return number of parameters to adjust
*/
public int getParameterToAdjust() {
return parameterToAdjust;
}
@After
public void tearDown() {
}
}
package org.orekit.rugged.adjustment.util;
import java.util.ArrayList;
import java.util.List;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.RotationOrder;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.util.FastMath;
import org.orekit.attitudes.AttitudeProvider;
import org.orekit.attitudes.LofOffset;
import org.orekit.attitudes.NadirPointing;
import org.orekit.attitudes.TabulatedLofOffset;
import org.orekit.attitudes.YawCompensation;
import org.orekit.bodies.BodyShape;
import org.orekit.frames.Frame;
import org.orekit.frames.FramesFactory;
import org.orekit.frames.LOFType;
import org.orekit.orbits.CircularOrbit;
import org.orekit.orbits.Orbit;
import org.orekit.orbits.PositionAngle;
import org.orekit.propagation.Propagator;
import org.orekit.propagation.analytical.KeplerianPropagator;
import org.orekit.time.AbsoluteDate;
import org.orekit.utils.AngularDerivativesFilter;
import org.orekit.utils.Constants;
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.utils.TimeStampedPVCoordinates;
/**
* Class to compute Pleiades orbit for refining Junit tests.
*/
public class PleiadesOrbitModel {
/** Flag to change Attitude Law (by default Nadir Pointing Yaw Compensation). */
private boolean userDefinedLOFTransform;
/** User defined Roll law. */
private double[] lofTransformRollPoly;
/** User defined Pitch law. */
private double[] lofTransformPitchPoly;
/** User defined Yaw law. */
private double[] lofTransformYawPoly;
/** Reference date. */
private AbsoluteDate refDate;
/** Default constructor.
*/
public PleiadesOrbitModel() {
userDefinedLOFTransform = false;
}
/** Create a circular orbit.
*/
public Orbit createOrbit(final double mu, final AbsoluteDate date) {
// the following orbital parameters have been computed using
// Orekit tutorial about phasing, using the following configuration:
//
// orbit.date = 2012-01-01T00:00:00.000
// phasing.orbits.number = 143
// phasing.days.number = 10
// sun.synchronous.reference.latitude = 0
// sun.synchronous.reference.ascending = false
// sun.synchronous.mean.solar.time = 10:30:00
// gravity.field.degree = 12
// gravity.field.order = 12
final Frame eme2000 = FramesFactory.getEME2000();
return new CircularOrbit(694000.0 + Constants.WGS84_EARTH_EQUATORIAL_RADIUS,
-4.029194321683225E-4,
0.0013530362644647786,
FastMath.toRadians(98.2), // Pleiades inclination 98.2 deg
FastMath.toRadians(-86.47 + 180),
FastMath.toRadians(135.9 + 0.3),
PositionAngle.TRUE,
eme2000,
date,
mu);
}
/** Set the Local Orbital Frame characteristics.
*/
public void setLOFTransform(final double[] rollPoly, final double[] pitchPoly,
final double[] yawPoly, final AbsoluteDate date) {
this.userDefinedLOFTransform = true;
lofTransformRollPoly = rollPoly.clone();
lofTransformPitchPoly = pitchPoly.clone();
lofTransformYawPoly = yawPoly.clone();
this.refDate = date;
}
/** Recompute the polynom coefficients with shift.
*/
private double getPoly(final double[] poly, final double shift) {
double val = 0.0;
for (int coef = 0; coef < poly.length; coef++) {
val = val + poly[coef] * FastMath.pow(shift, coef);
}
return val;
}
/** Get the offset.
*/
private Rotation getOffset(final BodyShape earth, final Orbit orbit, final double shift) {
final LOFType type = LOFType.VVLH;
final double roll = getPoly(lofTransformRollPoly, shift);
final double pitch = getPoly(lofTransformPitchPoly, shift);
final double yaw = getPoly(lofTransformYawPoly, shift);
final LofOffset law = new LofOffset(orbit.getFrame(), type, RotationOrder.XYZ,
roll, pitch, yaw);
final Rotation offsetAtt = law.
getAttitude(orbit, orbit.getDate().shiftedBy(shift), orbit.getFrame()).
getRotation();
final NadirPointing nadirPointing = new NadirPointing(orbit.getFrame(), earth);
final Rotation nadirAtt = nadirPointing.
getAttitude(orbit, orbit.getDate().getDate().shiftedBy(shift), orbit.getFrame()).
getRotation();
final Rotation offsetProper = offsetAtt.compose(nadirAtt.revert(), RotationConvention.VECTOR_OPERATOR);
return offsetProper;
}
/** Create the attitude provider.
*/
public AttitudeProvider createAttitudeProvider(final BodyShape earth, final Orbit orbit) {
if (userDefinedLOFTransform) {
final LOFType type = LOFType.VVLH;
final List<TimeStampedAngularCoordinates> list = new ArrayList<TimeStampedAngularCoordinates>();
for (double shift = -10.0; shift < +10.0; shift += 1e-2) {
list.add(new TimeStampedAngularCoordinates(refDate.shiftedBy(shift),
getOffset(earth, orbit, shift),
Vector3D.ZERO,
Vector3D.ZERO));
}
final TabulatedLofOffset tabulated = new TabulatedLofOffset(orbit.getFrame(), type, list,
2, AngularDerivativesFilter.USE_R);
return tabulated;
} else {
return new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth));
}
}
/** Generate the orbit.
*/
public List<TimeStampedPVCoordinates> orbitToPV(final Orbit orbit, final BodyShape earth,
final AbsoluteDate minDate, final AbsoluteDate maxDate,
final double step) {
final Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(createAttitudeProvider(earth, orbit));
propagator.propagate(minDate);
final List<TimeStampedPVCoordinates> list = new ArrayList<TimeStampedPVCoordinates>();
propagator.getMultiplexer().add(step,
currentState -> list.add(new TimeStampedPVCoordinates(currentState.getDate(),
currentState.getPVCoordinates().getPosition(),
currentState.getPVCoordinates().getVelocity(),
Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
/** Generate the attitude.
*/
public List<TimeStampedAngularCoordinates> orbitToQ(final Orbit orbit, final BodyShape earth,
final AbsoluteDate minDate, final AbsoluteDate maxDate,
final double step) {
final Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(createAttitudeProvider(earth, orbit));
propagator.propagate(minDate);
final List<TimeStampedAngularCoordinates> list = new ArrayList<>();
propagator.getMultiplexer().add(step,
currentState -> list.add(new TimeStampedAngularCoordinates(currentState.getDate(),
currentState.getAttitude().getRotation(),
Vector3D.ZERO,
Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
}
package org.orekit.rugged.adjustment.util;
import java.util.ArrayList;
import java.util.List;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.util.FastMath;
import org.orekit.rugged.linesensor.LineDatation;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.LinearLineDatation;
import org.orekit.rugged.los.FixedRotation;
import org.orekit.rugged.los.FixedZHomothety;
import org.orekit.rugged.los.LOSBuilder;
import org.orekit.rugged.los.TimeDependentLOS;
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScale;
import org.orekit.time.TimeScalesFactory;
/**
* Pleiades viewing model for refining Junit tests.
*/
public class PleiadesViewingModel {
/** Pleiades parameters. */
private static final double FOV = 1.65; // 20km - alt 694km
private static final int DIMENSION = 40000;
private static final double LINE_PERIOD = 1.e-4;
private double incidenceAngle;
private LineSensor lineSensor;
private String referenceDate;
private String sensorName;
/** PleiadesViewingModel constructor.
* @param sensorName sensor name
* @param incidenceAngle incidence angle
* @param referenceDate reference date
*/
public PleiadesViewingModel(final String sensorName, final double incidenceAngle, final String referenceDate) {
this.sensorName = sensorName;
this.referenceDate = referenceDate;
this.incidenceAngle = incidenceAngle;
this.createLineSensor();
}
/** Create raw fixed Line Of sight
*/
public LOSBuilder rawLOS(final Vector3D center, final Vector3D normal, final double halfAperture, final int n) {
final List<Vector3D> list = new ArrayList<Vector3D>(n);
for (int i = 0; i < n; ++i) {
final double alpha = (halfAperture * (2 * i + 1 - n)) / (n - 1);
list.add(new Rotation(normal, alpha, RotationConvention.VECTOR_OPERATOR).applyTo(center));
}
return new LOSBuilder(list);
}
/** Build a LOS provider
*/
public TimeDependentLOS buildLOS() {
final LOSBuilder losBuilder = rawLOS(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(incidenceAngle),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I, FastMath.toRadians(FOV / 2), DIMENSION);
losBuilder.addTransform(new FixedRotation(sensorName + InitInterRefiningTest.rollSuffix, Vector3D.MINUS_I, 0.00));
losBuilder.addTransform(new FixedRotation(sensorName + InitInterRefiningTest.pitchSuffix, Vector3D.MINUS_J, 0.00));
// factor is a common parameters shared between all Pleiades models
losBuilder.addTransform(new FixedZHomothety(InitInterRefiningTest.factorName, 1.0));
return losBuilder.build();
}
/** Get the reference date.
*/
public AbsoluteDate getDatationReference() {
// We use Orekit for handling time and dates, and Rugged for defining the datation model:
final TimeScale utc = TimeScalesFactory.getUTC();
return new AbsoluteDate(referenceDate, utc);
}
/** Get the min date.
*/
public AbsoluteDate getMinDate() {
return lineSensor.getDate(0);
}
/** Get the max date.
*/
public AbsoluteDate getMaxDate() {
return lineSensor.getDate(DIMENSION);
}
/** Get the line sensor.
*/
public LineSensor getLineSensor() {
return lineSensor;
}
/** Get the sensor name.
*/
public String getSensorName() {
return sensorName;
}
/** Get the number of lines of the sensor.
* @return the number of lines of the sensor
*/
public int getDimension() {
return DIMENSION;
}
/** Create the line sensor.
*/
private void createLineSensor() {
// Offset of the MSI from center of mass of satellite
// one line sensor
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
final Vector3D msiOffset = new Vector3D(0, 0, 0);
final TimeDependentLOS lineOfSight = buildLOS();
final double rate = 1. / LINE_PERIOD;
// linear datation model: at reference time we get the middle line, and the rate is one line every 1.5ms
final LineDatation lineDatation = new LinearLineDatation(getDatationReference(), DIMENSION / 2, rate);
lineSensor = new LineSensor(sensorName, lineDatation, msiOffset, lineOfSight);
}
}
package org.orekit.rugged.adjustment.util;
import org.orekit.rugged.api.Rugged;
import org.orekit.utils.ParameterDriver;
/** Apply disruptions or select/unselect parameter to adjust for Refining JUnit tests.
* @author Guylaine Prat
*/
public class RefiningParametersDriver {
// Part of the name of parameter drivers
static final String rollSuffix = "_roll";
static final String pitchSuffix = "_pitch";
static final String factorName = "factor";
/** Apply disruptions on acquisition for roll angle
* @param rugged Rugged instance
* @param sensorName line sensor name
* @param rollValue rotation on roll value
*/
public static void applyDisruptionsRoll(final Rugged rugged, final String sensorName, final double rollValue) {
rugged.
getLineSensor(sensorName).
getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + rollSuffix)).
findFirst().get().setValue(rollValue);
}
/** Apply disruptions on acquisition for pitch angle
* @param rugged Rugged instance
* @param sensorName line sensor name
* @param pitchValue rotation on pitch value
*/
public static void applyDisruptionsPitch(final Rugged rugged, final String sensorName, final double pitchValue) {
rugged.
getLineSensor(sensorName).
getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + pitchSuffix)).
findFirst().get().setValue(pitchValue);
}
/** Apply disruptions on acquisition for scale factor
* @param rugged Rugged instance
* @param sensorName line sensor name
* @param factorValue scale factor
*/
public static void applyDisruptionsFactor(final Rugged rugged, final String sensorName, final double factorValue) {
rugged.
getLineSensor(sensorName).
getParametersDrivers().
filter(driver -> driver.getName().equals(factorName)).
findFirst().get().setValue(factorValue);
}
/** Select roll angle to adjust
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void setSelectedRoll(final Rugged rugged, final String sensorName) {
ParameterDriver rollDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + rollSuffix)).findFirst().get();
rollDriver.setSelected(true);
}
/** Select pitch angle to adjust
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void setSelectedPitch(final Rugged rugged, final String sensorName) {
ParameterDriver pitchDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + pitchSuffix)).findFirst().get();
pitchDriver.setSelected(true);
}
/** Select scale factor to adjust
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void setSelectedFactor(final Rugged rugged, final String sensorName) {
ParameterDriver factorDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(factorName)).findFirst().get();
factorDriver.setSelected(true);
}
/** Unselect roll angle to adjust (for test coverage purpose)
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void unselectRoll(final Rugged rugged, final String sensorName) {
ParameterDriver rollDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + rollSuffix)).findFirst().get();
rollDriver.setSelected(false);
}
/** Unselect pitch angle to adjust (for test coverage purpose)
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void unselectPitch(final Rugged rugged, final String sensorName) {
ParameterDriver pitchDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(sensorName + pitchSuffix)).findFirst().get();
pitchDriver.setSelected(false);
}
/** Unselect factor angle to adjust (for test coverage purpose)
* @param rugged Rugged instance
* @param sensorName line sensor name
*/
public static void unselectFactor(final Rugged rugged, final String sensorName) {
ParameterDriver factorDriver =
rugged.getLineSensor(sensorName).getParametersDrivers().
filter(driver -> driver.getName().equals(factorName)).findFirst().get();
factorDriver.setSelected(false);
}
}
/* 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,11 +17,6 @@
package org.orekit.rugged.api;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.ode.nonstiff.DormandPrince853Integrator;
import org.hipparchus.util.FastMath;
import java.io.ByteArrayInputStream;
import java.io.ByteArrayOutputStream;
import java.io.EOFException;
......@@ -29,11 +24,17 @@ import java.io.File;
import java.io.FileOutputStream;
import java.io.IOException;
import java.io.StreamCorruptedException;
import java.lang.reflect.Field;
import java.net.URISyntaxException;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.List;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.ode.nonstiff.DormandPrince853Integrator;
import org.hipparchus.util.FastMath;
import org.junit.Assert;
import org.junit.Rule;
import org.junit.Test;
......@@ -45,9 +46,8 @@ import org.orekit.bodies.BodyShape;
import org.orekit.bodies.CelestialBodyFactory;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.bodies.OneAxisEllipsoid;
import org.orekit.data.DataProvidersManager;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.forces.gravity.HolmesFeatherstoneAttractionModel;
import org.orekit.forces.gravity.ThirdBodyAttraction;
import org.orekit.forces.gravity.potential.GravityFieldFactory;
......@@ -63,7 +63,6 @@ import org.orekit.propagation.Propagator;
import org.orekit.propagation.SpacecraftState;
import org.orekit.propagation.analytical.KeplerianPropagator;
import org.orekit.propagation.numerical.NumericalPropagator;
import org.orekit.propagation.sampling.OrekitFixedStepHandler;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.linesensor.LineDatation;
......@@ -74,6 +73,10 @@ import org.orekit.rugged.los.TimeDependentLOS;
import org.orekit.rugged.raster.RandomLandscapeUpdater;
import org.orekit.rugged.raster.TileUpdater;
import org.orekit.rugged.raster.VolcanicConeElevationUpdater;
import org.orekit.rugged.refraction.AtmosphericRefraction;
import org.orekit.rugged.refraction.ConstantRefractionLayer;
import org.orekit.rugged.refraction.MultiLayerModel;
import org.orekit.rugged.utils.ExtendedEllipsoid;
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScale;
import org.orekit.time.TimeScalesFactory;
......@@ -92,10 +95,10 @@ public class RuggedBuilderTest {
@Test
public void testSetContextWithEphemerides()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException, NoSuchFieldException, SecurityException, IllegalArgumentException, IllegalAccessException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
AbsoluteDate t0 = new AbsoluteDate("2012-01-01T00:00:00", TimeScalesFactory.getUTC());
List<TimeStampedPVCoordinates> pv = Arrays.asList(
......@@ -195,7 +198,36 @@ public class RuggedBuilderTest {
Assert.assertFalse(rugged.isAberrationOfLightCorrected());
Assert.assertFalse(builder.getLightTimeCorrection());
Assert.assertFalse(builder.getAberrationOfLightCorrection());
AtmosphericRefraction atmosphericRefraction = new MultiLayerModel(builder.getEllipsoid());
builder.setRefractionCorrection(atmosphericRefraction);
rugged = builder.build();
MultiLayerModel atmosphericRefractionFromBuilder = (MultiLayerModel) builder.getRefractionCorrection();
Field atmos = atmosphericRefractionFromBuilder.getClass().getDeclaredField("ellipsoid");
atmos.setAccessible(true);
ExtendedEllipsoid ellipsoidAtmos = (ExtendedEllipsoid) atmos.get(atmosphericRefractionFromBuilder);
Assert.assertEquals(builder.getEllipsoid().getEquatorialRadius(), ellipsoidAtmos.getEquatorialRadius(), 1.0e-9);
Assert.assertEquals(builder.getEllipsoid().getFlattening(), ellipsoidAtmos.getFlattening(), 1.0e-10);
Field layers = atmosphericRefractionFromBuilder.getClass().getDeclaredField("refractionLayers");
layers.setAccessible(true);
@SuppressWarnings("unchecked")
List<ConstantRefractionLayer> layersAtmos = (List<ConstantRefractionLayer>) layers.get(atmosphericRefractionFromBuilder);
Field layersExpected = atmosphericRefraction.getClass().getDeclaredField("refractionLayers");
layersExpected.setAccessible(true);
@SuppressWarnings("unchecked")
List<ConstantRefractionLayer> layersAtmosExpected = (List<ConstantRefractionLayer>) layersExpected.get(atmosphericRefraction);
Assert.assertEquals(layersAtmosExpected.size(), layersAtmos.size());
List<ConstantRefractionLayer> copyAtmosExpected = new ArrayList<ConstantRefractionLayer>(layersAtmosExpected);
List<ConstantRefractionLayer> copyAtmos = new ArrayList<ConstantRefractionLayer>(layersAtmos);
Assert.assertTrue(copyAtmosExpected.removeAll(layersAtmos) && copyAtmos.removeAll(layersAtmosExpected));
Assert.assertTrue(copyAtmosExpected.isEmpty() && copyAtmos.isEmpty());
Assert.assertEquals(AlgorithmId.DUVENHAGE, builder.getAlgorithm());
Assert.assertEquals(6378137.0, builder.getEllipsoid().getEquatorialRadius(), 1.0e-9);
Assert.assertEquals(1.0 / 298.257222101, builder.getEllipsoid().getFlattening(), 1.0e-10);
......@@ -279,10 +311,10 @@ public class RuggedBuilderTest {
@Test
public void testSetContextWithPropagator()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
BodyShape earth = createEarth();
NormalizedSphericalHarmonicsProvider gravityField = createGravityField();
Orbit orbit = createOrbit(gravityField.getMu());
......@@ -324,10 +356,10 @@ public class RuggedBuilderTest {
@Test
public void testOutOfTimeRange()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
AbsoluteDate t0 = new AbsoluteDate("2012-01-01T00:00:00", TimeScalesFactory.getUTC());
List<TimeStampedPVCoordinates> pv = Arrays.asList(
......@@ -426,12 +458,12 @@ public class RuggedBuilderTest {
@Test
public void testInterpolatorDump()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = createEarth();
final Orbit orbit = createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -495,12 +527,12 @@ public class RuggedBuilderTest {
@Test
public void testInterpolatorCannotDump()
throws RuggedException, OrekitException, URISyntaxException, IOException {
throws URISyntaxException, IOException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = createEarth();
final Orbit orbit = createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -542,15 +574,15 @@ public class RuggedBuilderTest {
Assert.assertEquals(IOException.class, re.getCause().getClass());
}
}
@Test
public void testInterpolatorDumpWrongFrame()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = createEarth();
final Orbit orbit = createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -606,10 +638,10 @@ public class RuggedBuilderTest {
@Test
public void testInterpolatorNotADump()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
// the following array is a real serialization file corresponding to the following
// made-up empty class that does not exist in Rugged:
......@@ -678,8 +710,7 @@ public class RuggedBuilderTest {
protected void addSatellitePV(TimeScale gps, Frame eme2000, Frame itrf,
ArrayList<TimeStampedPVCoordinates> satellitePVList,
String absDate,
double px, double py, double pz, double vx, double vy, double vz)
throws OrekitException {
double px, double py, double pz, double vx, double vy, double vz) {
AbsoluteDate ephemerisDate = new AbsoluteDate(absDate, gps);
Vector3D position = new Vector3D(px, py, pz);
Vector3D velocity = new Vector3D(vx, vy, vz);
......@@ -699,20 +730,17 @@ public class RuggedBuilderTest {
satelliteQList.add(pair);
}
private BodyShape createEarth()
throws OrekitException {
private BodyShape createEarth() {
return new OneAxisEllipsoid(Constants.WGS84_EARTH_EQUATORIAL_RADIUS,
Constants.WGS84_EARTH_FLATTENING,
FramesFactory.getITRF(IERSConventions.IERS_2010, true));
}
private NormalizedSphericalHarmonicsProvider createGravityField()
throws OrekitException {
private NormalizedSphericalHarmonicsProvider createGravityField() {
return GravityFieldFactory.getNormalizedProvider(12, 12);
}
private Orbit createOrbit(double mu)
throws OrekitException {
private Orbit createOrbit(double mu) {
// the following orbital parameters have been computed using
// Orekit tutorial about phasing, using the following configuration:
//
......@@ -736,8 +764,7 @@ public class RuggedBuilderTest {
private Propagator createPropagator(BodyShape earth,
NormalizedSphericalHarmonicsProvider gravityField,
Orbit orbit)
throws OrekitException {
Orbit orbit) {
AttitudeProvider yawCompensation = new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth));
SpacecraftState state = new SpacecraftState(orbit,
......@@ -792,43 +819,30 @@ public class RuggedBuilderTest {
private List<TimeStampedPVCoordinates> orbitToPV(Orbit orbit, BodyShape earth,
AbsoluteDate minDate, AbsoluteDate maxDate,
double step)
throws OrekitException {
double step) {
Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)));
propagator.propagate(minDate);
final List<TimeStampedPVCoordinates> list = new ArrayList<TimeStampedPVCoordinates>();
propagator.setMasterMode(step, new OrekitFixedStepHandler() {
public void init(SpacecraftState s0, AbsoluteDate t) {
}
public void handleStep(SpacecraftState currentState, boolean isLast) {
list.add(new TimeStampedPVCoordinates(currentState.getDate(),
currentState.getPVCoordinates().getPosition(),
currentState.getPVCoordinates().getVelocity(),
Vector3D.ZERO));
}
});
propagator.getMultiplexer().add(step, currentState -> list.add(new TimeStampedPVCoordinates(currentState.getDate(),
currentState.getPVCoordinates().getPosition(),
currentState.getPVCoordinates().getVelocity(),
Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
private List<TimeStampedAngularCoordinates> orbitToQ(Orbit orbit, BodyShape earth,
AbsoluteDate minDate, AbsoluteDate maxDate,
double step)
throws OrekitException {
double step) {
Propagator propagator = new KeplerianPropagator(orbit);
propagator.setAttitudeProvider(new YawCompensation(orbit.getFrame(), new NadirPointing(orbit.getFrame(), earth)));
propagator.propagate(minDate);
final List<TimeStampedAngularCoordinates> list = new ArrayList<TimeStampedAngularCoordinates>();
propagator.setMasterMode(step, new OrekitFixedStepHandler() {
public void init(SpacecraftState s0, AbsoluteDate t) {
}
public void handleStep(SpacecraftState currentState, boolean isLast) {
list.add(new TimeStampedAngularCoordinates(currentState.getDate(),
currentState.getAttitude().getRotation(),
Vector3D.ZERO, Vector3D.ZERO));
}
});
propagator.getMultiplexer().add(step, currentState -> list.add(new TimeStampedAngularCoordinates(currentState.getDate(),
currentState.getAttitude().getRotation(),
Vector3D.ZERO, Vector3D.ZERO)));
propagator.propagate(maxDate);
return list;
}
......
/* 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,6 +17,10 @@
package org.orekit.rugged.api;
import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertNull;
import static org.junit.Assert.assertTrue;
import java.io.File;
import java.io.IOException;
import java.io.RandomAccessFile;
......@@ -26,41 +30,45 @@ import java.net.URISyntaxException;
import java.nio.MappedByteBuffer;
import java.nio.channels.FileChannel;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collections;
import java.util.List;
import java.util.Locale;
import org.hipparchus.analysis.differentiation.DerivativeStructure;
import org.hipparchus.analysis.differentiation.DSFactory;
import org.hipparchus.analysis.differentiation.FiniteDifferencesDifferentiator;
import org.hipparchus.analysis.differentiation.Gradient;
import org.hipparchus.analysis.differentiation.UnivariateDifferentiableFunction;
import org.hipparchus.geometry.euclidean.threed.Rotation;
import org.hipparchus.geometry.euclidean.threed.RotationConvention;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresOptimizer.Optimum;
import org.hipparchus.stat.descriptive.StreamingStatistics;
import org.hipparchus.stat.descriptive.rank.Percentile;
import org.hipparchus.util.FastMath;
import org.junit.Assert;
import org.junit.Before;
import org.junit.Ignore;
import org.junit.Rule;
import org.junit.Test;
import org.junit.rules.TemporaryFolder;
import org.orekit.bodies.BodyShape;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.data.DataProvidersManager;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.errors.OrekitExceptionWrapper;
import org.orekit.forces.gravity.potential.NormalizedSphericalHarmonicsProvider;
import org.orekit.frames.Frame;
import org.orekit.frames.FramesFactory;
import org.orekit.orbits.Orbit;
import org.orekit.propagation.EphemerisGenerator;
import org.orekit.propagation.Propagator;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.adjustment.GroundOptimizationProblemBuilder;
import org.orekit.rugged.adjustment.measurements.Observables;
import org.orekit.rugged.adjustment.util.InitInterRefiningTest;
import org.orekit.rugged.errors.RuggedException;
import org.orekit.rugged.errors.RuggedExceptionWrapper;
import org.orekit.rugged.errors.RuggedMessages;
import org.orekit.rugged.intersection.IgnoreDEMAlgorithm;
import org.orekit.rugged.intersection.IntersectionAlgorithm;
import org.orekit.rugged.linesensor.LineDatation;
import org.orekit.rugged.linesensor.LineSensor;
import org.orekit.rugged.linesensor.LinearLineDatation;
......@@ -71,7 +79,9 @@ import org.orekit.rugged.los.TimeDependentLOS;
import org.orekit.rugged.raster.RandomLandscapeUpdater;
import org.orekit.rugged.raster.TileUpdater;
import org.orekit.rugged.raster.VolcanicConeElevationUpdater;
import org.orekit.rugged.utils.DSGenerator;
import org.orekit.rugged.refraction.AtmosphericRefraction;
import org.orekit.rugged.utils.DerivativeGenerator;
import org.orekit.rugged.utils.NormalizedGeodeticPoint;
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScale;
import org.orekit.time.TimeScalesFactory;
......@@ -83,6 +93,7 @@ import org.orekit.utils.ParameterDriver;
import org.orekit.utils.TimeStampedAngularCoordinates;
import org.orekit.utils.TimeStampedPVCoordinates;
public class RuggedTest {
@Rule
......@@ -93,13 +104,13 @@ public class RuggedTest {
@Ignore
@Test
public void testMayonVolcanoTiming()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
long t0 = System.currentTimeMillis();
int dimension = 2000;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
BodyShape earth = TestUtils.createEarth();
NormalizedSphericalHarmonicsProvider gravityField = TestUtils.createGravityField();
Orbit orbit = TestUtils.createOrbit(gravityField.getMu());
......@@ -118,7 +129,8 @@ public class RuggedTest {
// los: swath in the (YZ) plane, centered at +Z, ±10° aperture, 960 pixels
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(Vector3D.PLUS_K, Vector3D.PLUS_I,
FastMath.toRadians(10.0), dimension).build();
FastMath.toRadians(10.0), dimension).
build();
// linear datation model: at reference time we get line 1000, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
......@@ -128,9 +140,9 @@ public class RuggedTest {
Propagator propagator = TestUtils.createPropagator(earth, gravityField, orbit);
propagator.propagate(lineDatation.getDate(firstLine).shiftedBy(-1.0));
propagator.setEphemerisMode();
final EphemerisGenerator generator = propagator.getEphemerisGenerator();
propagator.propagate(lineDatation.getDate(lastLine).shiftedBy(+1.0));
Propagator ephemeris = propagator.getGeneratedEphemeris();
Propagator ephemeris = generator.getGeneratedEphemeris();
Rugged rugged = new RuggedBuilder().
setDigitalElevationModel(updater, 8).
......@@ -183,12 +195,12 @@ public class RuggedTest {
@Test
public void testLightTimeCorrection()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 400;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -261,12 +273,12 @@ public class RuggedTest {
@Test
public void testAberrationOfLightCorrection()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 400;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -314,17 +326,16 @@ public class RuggedTest {
Assert.assertTrue(Vector3D.distance(pWith, pWithout) > 20.0);
Assert.assertTrue(Vector3D.distance(pWith, pWithout) < 20.5);
}
}
@Test
public void testFlatBodyCorrection()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -380,13 +391,13 @@ public class RuggedTest {
}
@Test
public void testLocationsinglePoint()
throws RuggedException, OrekitException, URISyntaxException {
public void testLocationSinglePoint()
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -439,12 +450,12 @@ public class RuggedTest {
@Test
public void testLocationsinglePointNoCorrections()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -500,12 +511,12 @@ public class RuggedTest {
@Test
public void testBasicScan()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -563,14 +574,14 @@ public class RuggedTest {
@Ignore
@Test
public void testInverseLocationTiming()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
long t0 = System.currentTimeMillis();
int dimension = 2000;
int nbSensors = 3;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -580,12 +591,12 @@ public class RuggedTest {
for (int i = 0; i < nbSensors; ++i) {
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking roughly at 50° roll (sensor-dependent), 2.6" per pixel
// los: swath in the (YZ) plane, looking roughly at 50° roll (sensor-dependent), 5.2" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0 - 0.001 * i),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I, FastMath.toRadians(dimension * 2.6 / 3600.0), dimension).build();
Vector3D.PLUS_I, FastMath.toRadians((dimension/2.) * 5.2 / 3600.0), dimension).build();
// linear datation model: at reference time we get roughly middle line, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, i + dimension / 2, 1.0 / 1.5e-3);
......@@ -673,7 +684,7 @@ public class RuggedTest {
@Test
public void testInverseLocation()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
checkInverseLocation(2000, false, false, 4.0e-7, 5.0e-6);
checkInverseLocation(2000, false, true, 1.0e-5, 2.0e-7);
checkInverseLocation(2000, true, false, 4.0e-7, 4.0e-7);
......@@ -682,18 +693,26 @@ public class RuggedTest {
@Test
public void testDateLocation()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
checkDateLocation(2000, false, false, 7.0e-7);
checkDateLocation(2000, false, true, 2.0e-5);
checkDateLocation(2000, true, false, 8.0e-7);
checkDateLocation(2000, true, true, 3.0e-6);
}
@Test
public void testLineDatation()
throws URISyntaxException {
checkLineDatation(2000, 7.0e-7);
checkLineDatation(10000, 8.0e-7);
}
@Test
public void testInverseLocNearLineEnd() throws OrekitException, RuggedException, URISyntaxException {
public void testInverseLocNearLineEnd() throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
Vector3D offset = Vector3D.ZERO;
TimeScale gps = TimeScalesFactory.getGPS();
Frame eme2000 = FramesFactory.getEME2000();
......@@ -792,10 +811,10 @@ public class RuggedTest {
}
@Test
public void testInverseLoc() throws OrekitException, RuggedException, URISyntaxException {
public void testInverseLoc() throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
Vector3D offset = Vector3D.ZERO;
TimeScale gps = TimeScalesFactory.getGPS();
Frame eme2000 = FramesFactory.getEME2000();
......@@ -864,6 +883,17 @@ public class RuggedTest {
LinearLineDatation lineDatation = new LinearLineDatation(absDate, 0.03125d, 19.95565693384045);
LineSensor lineSensor = new LineSensor("QUICK_LOOK", lineDatation, offset,
new LOSBuilder(lineOfSight).build());
// in order not to have a problem when calling the pixelIsInside method (AtmosphericRefraction must be not null)
AtmosphericRefraction atmos = new AtmosphericRefraction() {
@Override
public NormalizedGeodeticPoint applyCorrection(Vector3D satPos, Vector3D satLos,
NormalizedGeodeticPoint rawIntersection, IntersectionAlgorithm algorithm) {
return rawIntersection;
}
};
atmos.deactivateComputation();
Rugged rugged = new RuggedBuilder().
setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID).
setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF).
......@@ -873,6 +903,7 @@ public class RuggedTest {
satellitePVList, 6, CartesianDerivativesFilter.USE_P,
satelliteQList, 8, AngularDerivativesFilter.USE_R).
addLineSensor(lineSensor).
setRefractionCorrection(atmos).
build();
GeodeticPoint[] temp = rugged.directLocation("QUICK_LOOK", -250);
......@@ -889,14 +920,36 @@ public class RuggedTest {
Assert.assertNotNull(sensorPixel);
Assert.assertFalse(inside(rugged, null, lineSensor));
Assert.assertFalse(inside(rugged, new SensorPixel(-100, -100), lineSensor));
Assert.assertFalse(inside(rugged, new SensorPixel(-100, +100), lineSensor));
Assert.assertFalse(inside(rugged, new SensorPixel(+100, -100), lineSensor));
Assert.assertFalse(inside(rugged, new SensorPixel(+100, +100), lineSensor));
Assert.assertTrue(inside(rugged, new SensorPixel(0.2, 0.3), lineSensor));
}
private boolean inside(final Rugged rugged, final SensorPixel sensorPixel, LineSensor lineSensor) {
try {
final Method inside =
Rugged.class.getDeclaredMethod("pixelIsInside",
SensorPixel.class,
LineSensor.class);
inside.setAccessible(true);
return ((Boolean) inside.invoke(rugged, sensorPixel, lineSensor)).booleanValue();
} catch (NoSuchMethodException | IllegalAccessException |
IllegalArgumentException | InvocationTargetException e) {
Assert.fail(e.getLocalizedMessage());
return false;
}
}
@Test
public void testInverseLocCurvedLine()
throws RuggedException, URISyntaxException, OrekitException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -905,10 +958,10 @@ public class RuggedTest {
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at nadir, 2.6" per pixel, 3" sagitta
// los: swath in the (YZ) plane, looking at nadir, 5.2" per pixel, 3" sagitta
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSCurvedLine(Vector3D.PLUS_K, Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0),
FastMath.toRadians((dimension/2.) * 5.2 / 3600.0),
FastMath.toRadians(3.0 / 3600.0),
dimension);
......@@ -949,10 +1002,10 @@ public class RuggedTest {
private void checkInverseLocation(int dimension, boolean lightTimeCorrection, boolean aberrationOfLightCorrection,
double maxLineError, double maxPixelError)
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -960,13 +1013,14 @@ public class RuggedTest {
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
// los: swath in the (YZ) plane, looking at 50° roll, 5.2" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0),
FastMath.toRadians(5.0),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0), dimension).build();
FastMath.toRadians((dimension/2.) * 5.2 / 3600.0), dimension).build();
// In fact the pixel size = 5.2" as we construct the LOS with the full line (dimension) instead of dimension/2
// linear datation model: at reference time we get the middle line, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
......@@ -1005,6 +1059,7 @@ public class RuggedTest {
(1 - d) * gp[i].getLatitude() + d * gp[i + 1].getLatitude(),
(1 - d) * gp[i].getLongitude() + d * gp[i + 1].getLongitude(),
0, dimension);
Assert.assertEquals(referenceLine, sp.getLineNumber(), maxLineError);
Assert.assertEquals(p, sp.getPixelNumber(), maxPixelError);
}
......@@ -1041,32 +1096,41 @@ public class RuggedTest {
@Test
public void testInverseLocationDerivativesWithoutCorrections()
throws RuggedException, OrekitException {
{
doTestInverseLocationDerivatives(2000, false, false,
7.0e-9, 4.0e-11, 2.0e-12, 7.0e-8);
8.0e-9, 3.0e-10, 5.0e-12, 9.0e-8);
}
@Test
public void testInverseLocationDerivativesWithLightTimeCorrection()
throws RuggedException, OrekitException {
{
doTestInverseLocationDerivatives(2000, true, false,
3.0e-9, 9.0e-9, 3.0e-13, 7.0e-8);
3.0e-9, 9.0e-9, 2.1e-12, 9.0e-8);
}
@Test
public void testInverseLocationDerivativesWithAberrationOfLightCorrection()
throws RuggedException, OrekitException {
{
doTestInverseLocationDerivatives(2000, false, true,
3.0e-10, 3.0e-10, 7.0e-13, 7.0e-8);
4.2e-10, 3.0e-10, 3.4e-12, 7.0e-8);
}
@Test
public void testInverseLocationDerivativesWithAllCorrections()
throws RuggedException, OrekitException {
{
doTestInverseLocationDerivatives(2000, true, true,
3.0e-10, 5.0e-10, 7.0e-14, 7.0e-8);
7.0e-10, 5.0e-10, 2.0e-12, 7.0e-8);
}
/**
* @param dimension
* @param lightTimeCorrection
* @param aberrationOfLightCorrection
* @param lineTolerance
* @param pixelTolerance
* @param lineDerivativeRelativeTolerance
* @param pixelDerivativeRelativeTolerance
*/
private void doTestInverseLocationDerivatives(int dimension,
boolean lightTimeCorrection,
boolean aberrationOfLightCorrection,
......@@ -1074,11 +1138,11 @@ public class RuggedTest {
double pixelTolerance,
double lineDerivativeRelativeTolerance,
double pixelDerivativeRelativeTolerance)
throws RuggedException, OrekitException {
{
try {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -1086,17 +1150,18 @@ public class RuggedTest {
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
// los: swath in the (YZ) plane, looking at 50° roll, 5.2" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
LOSBuilder losBuilder =
TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0), dimension);
FastMath.toRadians((dimension/2.) * 5.2 / 3600.0), dimension);
losBuilder.addTransform(new FixedRotation("roll", Vector3D.MINUS_I, 0.0));
losBuilder.addTransform(new FixedRotation("pitch", Vector3D.MINUS_J, 0.0));
TimeDependentLOS los = losBuilder.build();
// In fact the pixel size = 5.2" as we construct the LOS with the full line (dimension) instead of dimension/2
// linear datation model: at reference time we get the middle line, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
......@@ -1136,9 +1201,15 @@ public class RuggedTest {
pitchDriver.setSelected(true);
// prepare generator
Method createGenerator = Rugged.class.getDeclaredMethod("createGenerator", List.class);
createGenerator.setAccessible(true);
DSGenerator generator = (DSGenerator) createGenerator.invoke(rugged, Collections.singletonList(lineSensor));
final Observables measurements = new Observables(1);
GroundOptimizationProblemBuilder optimizationPbBuilder = new GroundOptimizationProblemBuilder(Collections.singletonList(lineSensor),
measurements, rugged);
java.lang.reflect.Method getGenerator = GroundOptimizationProblemBuilder.class.getSuperclass().getDeclaredMethod("getGenerator");
getGenerator.setAccessible(true);
@SuppressWarnings("unchecked")
DerivativeGenerator<Gradient> generator = (DerivativeGenerator<Gradient>) getGenerator.invoke(optimizationPbBuilder);
double referenceLine = 0.87654 * dimension;
GeodeticPoint[] gp = rugged.directLocation("line", referenceLine);
......@@ -1146,327 +1217,74 @@ public class RuggedTest {
Method inverseLoc = Rugged.class.getDeclaredMethod("inverseLocationDerivatives",
String.class, GeodeticPoint.class,
Integer.TYPE, Integer.TYPE,
DSGenerator.class);
DerivativeGenerator.class);
inverseLoc.setAccessible(true);
int referencePixel = (3 * dimension) / 4;
DerivativeStructure[] result =
(DerivativeStructure[]) inverseLoc.invoke(rugged,
"line", gp[referencePixel], 0, dimension,
generator);
Gradient[] result =
(Gradient[]) inverseLoc.invoke(rugged,
"line", gp[referencePixel], 0, dimension,
generator);
Assert.assertEquals(referenceLine, result[0].getValue(), lineTolerance);
Assert.assertEquals(referencePixel, result[1].getValue(), pixelTolerance);
Assert.assertEquals(2, result[0].getFreeParameters());
Assert.assertEquals(1, result[0].getOrder());
// check the partial derivatives
DSFactory factory = new DSFactory(1, 1);
double h = 1.0e-6;
FiniteDifferencesDifferentiator differentiator = new FiniteDifferencesDifferentiator(8, h);
UnivariateDifferentiableFunction lineVSroll =
differentiator.differentiate((double roll) -> {
try {
rollDriver.setValue(roll);
pitchDriver.setValue(0);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber();
} catch (OrekitException e) {
throw new OrekitExceptionWrapper(e);
} catch (RuggedException e) {
throw new RuggedExceptionWrapper(e);
}
rollDriver.setValue(roll);
pitchDriver.setValue(0);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber();
});
double dLdR = lineVSroll.value(new DerivativeStructure(1, 1, 0, 0.0)).getPartialDerivative(1);
double dLdR = lineVSroll.value(factory.variable(0, 0.0)).getPartialDerivative(1);
Assert.assertEquals(dLdR, result[0].getPartialDerivative(1, 0), dLdR * lineDerivativeRelativeTolerance);
UnivariateDifferentiableFunction lineVSpitch =
differentiator.differentiate((double pitch) -> {
try {
rollDriver.setValue(0);
pitchDriver.setValue(pitch);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber();
} catch (OrekitException e) {
throw new OrekitExceptionWrapper(e);
} catch (RuggedException e) {
throw new RuggedExceptionWrapper(e);
}
rollDriver.setValue(0);
pitchDriver.setValue(pitch);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getLineNumber();
});
double dLdP = lineVSpitch.value(new DerivativeStructure(1, 1, 0, 0.0)).getPartialDerivative(1);
double dLdP = lineVSpitch.value(factory.variable(0, 0.0)).getPartialDerivative(1);
Assert.assertEquals(dLdP, result[0].getPartialDerivative(0, 1), dLdP * lineDerivativeRelativeTolerance);
UnivariateDifferentiableFunction pixelVSroll =
differentiator.differentiate((double roll) -> {
try {
rollDriver.setValue(roll);
pitchDriver.setValue(0);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber();
} catch (OrekitException e) {
throw new OrekitExceptionWrapper(e);
} catch (RuggedException e) {
throw new RuggedExceptionWrapper(e);
}
rollDriver.setValue(roll);
pitchDriver.setValue(0);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber();
});
double dXdR = pixelVSroll.value(new DerivativeStructure(1, 1, 0, 0.0)).getPartialDerivative(1);
double dXdR = pixelVSroll.value(factory.variable(0, 0.0)).getPartialDerivative(1);
Assert.assertEquals(dXdR, result[1].getPartialDerivative(1, 0), dXdR * pixelDerivativeRelativeTolerance);
UnivariateDifferentiableFunction pixelVSpitch =
differentiator.differentiate((double pitch) -> {
try {
rollDriver.setValue(0);
pitchDriver.setValue(pitch);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber();
} catch (OrekitException e) {
throw new OrekitExceptionWrapper(e);
} catch (RuggedException e) {
throw new RuggedExceptionWrapper(e);
}
rollDriver.setValue(0);
pitchDriver.setValue(pitch);
return rugged.inverseLocation("line", gp[referencePixel], 0, dimension).getPixelNumber();
});
double dXdP = pixelVSpitch.value(new DerivativeStructure(1, 1, 0, 0.0)).getPartialDerivative(1);
double dXdP = pixelVSpitch.value(factory.variable(0, 0.0)).getPartialDerivative(1);
Assert.assertEquals(dXdP, result[1].getPartialDerivative(0, 1), dXdP * pixelDerivativeRelativeTolerance);
} catch (InvocationTargetException | NoSuchMethodException |
SecurityException | IllegalAccessException |
IllegalArgumentException | URISyntaxException |
OrekitExceptionWrapper | RuggedExceptionWrapper e) {
SecurityException | IllegalAccessException |
IllegalArgumentException | URISyntaxException |
OrekitException | RuggedException e) {
Assert.fail(e.getLocalizedMessage());
}
}
@Test
public void testNoParametersSelected()
throws OrekitException {
try {
Rugged perfect = createParameterEstimationContext(2000, false, false).build();
perfect.estimateFreeParameters(Collections.singletonList(new SensorToGroundMapping("line")),
100, 1.0e-3);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.NO_PARAMETERS_SELECTED, re.getSpecifier());
}
}
@Test
public void testDuplicatedParameter()
throws OrekitException {
try {
TimeDependentLOS los =
TestUtils.createLOSPerfectLine(Vector3D.PLUS_K, Vector3D.PLUS_I, 0.1, 1000).
addTransform(new FixedRotation("pitch", Vector3D.MINUS_J, 0.0)).build();
LineDatation lineDatation = new LinearLineDatation(AbsoluteDate.J2000_EPOCH, 50, 1.0 / 1.5e-3);
Rugged perfect = createParameterEstimationContext(2000, false, false).
addLineSensor(new LineSensor("other", lineDatation, Vector3D.ZERO, los)).
build();
// the duplicated parameter is "pitch", it will be detected even despite only "roll" is estimated
perfect.getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("roll")).
forEach(driver -> driver.setSelected(true));
perfect.estimateFreeParameters(Arrays.asList(new SensorToGroundMapping("line"),
new SensorToGroundMapping("other")),
100, 1.0e-3);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.DUPLICATED_PARAMETER_NAME, re.getSpecifier());
Assert.assertEquals("pitch", re.getParts()[0]);
}
}
@Test
public void testNoReferenceMapping()
throws OrekitException {
try {
Rugged perfect = createParameterEstimationContext(2000, false, false).build();
perfect.getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("roll") || driver.getName().equals("pitch")).
forEach(driver -> driver.setSelected(true));
perfect.estimateFreeParameters(Collections.singletonList(new SensorToGroundMapping("line")),
100, 1.0e-3);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.NO_REFERENCE_MAPPINGS, re.getSpecifier());
}
}
@Test
public void testViewingModelParametersEstimationWithoutCorrections()
throws OrekitException, RuggedException {
doTestViewingModelParametersEstimation(2000, false, false,
FastMath.toRadians( 0.01), 1.0e-8,
FastMath.toRadians(-0.03), 2.0e-9,
6);
}
@Test
public void testViewingModelParametersEstimationWithLightTimeCorrection()
throws OrekitException, RuggedException {
doTestViewingModelParametersEstimation(2000, true, false,
FastMath.toRadians( 0.01), 1.0e-8,
FastMath.toRadians(-0.03), 2.0e-9,
6);
}
@Test
public void testViewingModelParametersEstimationWithAberrationOfLightCorrection()
throws OrekitException, RuggedException {
doTestViewingModelParametersEstimation(2000, false, true,
FastMath.toRadians( 0.01), 1.0e-8,
FastMath.toRadians(-0.03), 2.0e-9,
6);
}
@Test
public void testViewingModelParametersEstimationWithAllCorrections()
throws OrekitException, RuggedException {
doTestViewingModelParametersEstimation(2000, true, true,
FastMath.toRadians( 0.01), 1.0e-8,
FastMath.toRadians(-0.03), 3.0e-9,
6);
}
private void doTestViewingModelParametersEstimation(int dimension,
boolean lightTimeCorrection,
boolean aberrationOfLightCorrection,
double rollValue, double rollTolerance,
double pitchValue, double pitchTolerance,
int expectedEvaluations)
throws OrekitException, RuggedException {
try {
// set up a perfect Rugged instance, with prescribed roll and pitch values
Rugged perfect = createParameterEstimationContext(dimension,
lightTimeCorrection,
aberrationOfLightCorrection).build();
perfect.
getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("roll")).
findFirst().get().setValue(rollValue);
perfect.
getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("pitch")).
findFirst().get().setValue(pitchValue);
// generate reference mapping
SensorToGroundMapping mapping = new SensorToGroundMapping("line");
LineSensor sensor = perfect.getLineSensor(mapping.getSensorName());
for (double line = 0; line < dimension; line += 100) {
AbsoluteDate date = sensor.getDate(line);
for (int pixel = 0; pixel < sensor.getNbPixels(); pixel += 100) {
GeodeticPoint gp = perfect.directLocation(date, sensor.getPosition(),
sensor.getLOS(date, pixel));
mapping.addMapping(new SensorPixel(line, pixel), gp);
}
}
// set up a completely independent Rugged instance,
// with 0.0 roll and pitch values and estimating rool and pitch
Rugged normal = createParameterEstimationContext(dimension,
lightTimeCorrection,
aberrationOfLightCorrection).build();
normal.
getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("roll") || driver.getName().equals("pitch")).
forEach(driver -> {
try {
driver.setSelected(true);
driver.setValue(0.0);
} catch (OrekitException e) {
throw new OrekitExceptionWrapper(e);
}
});
// perform parameters estimation
Optimum optimum = normal.estimateFreeParameters(Collections.singletonList(mapping), 10, 1.0e-9);
Assert.assertEquals(expectedEvaluations, optimum.getEvaluations());
// check estimated values
double estimatedRoll = normal.getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("roll")).
findFirst().get().getValue();
Assert.assertEquals("roll error = " + (estimatedRoll - rollValue),
rollValue, estimatedRoll, rollTolerance);
double estimatedPitch = normal.getLineSensor("line").
getParametersDrivers().
filter(driver -> driver.getName().equals("pitch")).
findFirst().get().getValue();
Assert.assertEquals("pitch error = " + (estimatedPitch - pitchValue),
pitchValue, estimatedPitch, pitchTolerance);
} catch (OrekitExceptionWrapper oew) {
throw oew.getException();
}
}
private RuggedBuilder createParameterEstimationContext(int dimension,
boolean lightTimeCorrection,
boolean aberrationOfLightCorrection)
throws OrekitException, RuggedException {
try {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
AbsoluteDate crossing = new AbsoluteDate("2012-01-01T12:30:00.000", TimeScalesFactory.getUTC());
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
LOSBuilder losBuilder =
TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0), dimension);
losBuilder.addTransform(new FixedRotation("roll", Vector3D.MINUS_I, 0.0));
losBuilder.addTransform(new FixedRotation("pitch", Vector3D.MINUS_J, 0.0));
TimeDependentLOS los = losBuilder.build();
// linear datation model: at reference time we get the middle line, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
int firstLine = 0;
int lastLine = dimension;
final LineSensor lineSensor = new LineSensor("line", lineDatation, position, los);
AbsoluteDate minDate = lineSensor.getDate(firstLine).shiftedBy(-1.0);
AbsoluteDate maxDate = lineSensor.getDate(lastLine).shiftedBy(+1.0);
TileUpdater updater =
new RandomLandscapeUpdater(0.0, 9000.0, 0.3, 0xf0a401650191f9f6l,
FastMath.toRadians(1.0), 257);
return new RuggedBuilder().
setDigitalElevationModel(updater, 8).
setAlgorithm(AlgorithmId.DUVENHAGE).
setEllipsoid(EllipsoidId.WGS84, BodyRotatingFrameId.ITRF).
setTimeSpan(minDate, maxDate, 0.001, 5.0).
setTrajectory(InertialFrameId.EME2000,
TestUtils.orbitToPV(orbit, earth, minDate.shiftedBy(-1.0), maxDate.shiftedBy(+1.0), 0.25),
8, CartesianDerivativesFilter.USE_PV,
TestUtils.orbitToQ(orbit, earth, minDate.shiftedBy(-1.0), maxDate.shiftedBy(+1.0), 0.25),
2, AngularDerivativesFilter.USE_R).
setLightTimeCorrection(lightTimeCorrection).
setAberrationOfLightCorrection(aberrationOfLightCorrection).
addLineSensor(lineSensor);
} catch (URISyntaxException e) {
Assert.fail(e.getLocalizedMessage());
return null; // never reached
}
}
private void checkDateLocation(int dimension, boolean lightTimeCorrection, boolean aberrationOfLightCorrection,
double maxDateError)
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -1474,13 +1292,14 @@ public class RuggedTest {
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
// los: swath in the (YZ) plane, looking at 50° roll, 5.2" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0), dimension).build();
FastMath.toRadians((dimension/2.) * 5.2 / 3600.0), dimension).build();
// In fact the pixel size = 5.2" as we construct the LOS with the full line (dimension) instead of dimension/2
// linear datation model: at reference time we get line 100, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
......@@ -1537,8 +1356,206 @@ public class RuggedTest {
-20 * gp2[dimension / 2].getLatitude() + 21 * gp3[dimension / 2].getLatitude(),
-20 * gp2[dimension / 2].getLongitude() + 21 * gp3[dimension / 2].getLongitude(),
0, dimension));
}
private void checkLineDatation(int dimension, double maxLineError)
throws URISyntaxException {
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
AbsoluteDate crossing = new AbsoluteDate("2012-01-01T12:30:00.000", TimeScalesFactory.getUTC());
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, looking at 50° roll, 2.6" per pixel
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(new Rotation(Vector3D.PLUS_I,
FastMath.toRadians(50.0),
RotationConvention.VECTOR_OPERATOR).applyTo(Vector3D.PLUS_K),
Vector3D.PLUS_I,
FastMath.toRadians(dimension * 2.6 / 3600.0), dimension).build();
// In fact the pixel size = 5.2" as we construct the LOS with the full line (dimension) instead of dimension/2
// linear datation model: at reference time we get the middle line, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
int firstLine = 0;
int lastLine = dimension;
LineSensor lineSensor = new LineSensor("line", lineDatation, position, los);
AbsoluteDate minDate = lineSensor.getDate(firstLine).shiftedBy(-1.0);
AbsoluteDate maxDate = lineSensor.getDate(lastLine).shiftedBy(+1.0);
// Recompute the lines from the date with the appropriate shift of date
double recomputedFirstLine = lineSensor.getLine(minDate.shiftedBy(+1.0));
double recomputedLastLine = lineSensor.getLine(maxDate.shiftedBy(-1.0));
Assert.assertEquals(firstLine, recomputedFirstLine, maxLineError);
Assert.assertEquals(lastLine, recomputedLastLine, maxLineError);
}
@Test
public void testDistanceBetweenLOS() {
InitInterRefiningTest refiningTest = new InitInterRefiningTest();
refiningTest.initRefiningTest();
final SensorPixel realPixelA = new SensorPixel(2005.015883575199, 18004.968656395424);
final SensorPixel realPixelB = new SensorPixel(4798.487736488162, 13952.2195710654);
double[] distancesBetweenLOS = refiningTest.computeDistancesBetweenLOS(realPixelA, realPixelB);
double expectedDistanceBetweenLOS = 3.88800245;
double expectedDistanceToTheGround = 6368020.559109;
Assert.assertEquals(expectedDistanceBetweenLOS, distancesBetweenLOS[0], 1.e-8);
Assert.assertEquals(expectedDistanceToTheGround, distancesBetweenLOS[1], 1.e-5);
}
@Test
public void testDistanceBetweenLOSDerivatives() throws NoSuchMethodException, SecurityException, IllegalAccessException, IllegalArgumentException, InvocationTargetException {
InitInterRefiningTest refiningTest = new InitInterRefiningTest();
refiningTest.initRefiningTest();
final SensorPixel realPixelA = new SensorPixel(2005.015883575199, 18004.968656395424);
final SensorPixel realPixelB = new SensorPixel(4798.487736488162, 13952.2195710654);
// Expected distances between LOS and to the ground
double expectedDistanceBetweenLOS = 3.88800245;
double expectedDistanceToTheGround = 6368020.559109;
// Expected derivatives for
// minimum distance between LOS
double[] expectedDminDerivatives = {-153874.01319097, -678866.03112033, 191294.06938169, 668600.16715270} ;
// minimum distance to the ground
double[] expectedDcentralBodyDerivatives = {7007767.46926062, -1577060.82402054, -6839286.39593802, 1956452.66636262};
Gradient[] distancesBetweenLOSGradient = refiningTest.computeDistancesBetweenLOSGradient(realPixelA, realPixelB, expectedDistanceBetweenLOS, expectedDistanceToTheGround);
// Minimum distance between LOS
Gradient dMin = distancesBetweenLOSGradient[0];
// Minimum distance to the ground
Gradient dCentralBody = distancesBetweenLOSGradient[1];
Assert.assertEquals(expectedDistanceBetweenLOS, dMin.getValue(), 1.e-8);
Assert.assertEquals(expectedDistanceToTheGround, dCentralBody.getValue() , 1.e-5);
for (int i = 0; i < dMin.getFreeParameters(); i++) {
Assert.assertEquals(expectedDminDerivatives[i], dMin.getPartialDerivative(i), 1.e-8);
}
for (int i = 0; i < dCentralBody.getFreeParameters(); i++) {
Assert.assertEquals(expectedDcentralBodyDerivatives[i], dCentralBody.getPartialDerivative(i), 3.e-8);
}
}
@Test
public void testForCoverage() throws URISyntaxException {
int dimension = 400;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
AbsoluteDate crossing = new AbsoluteDate("2012-01-07T11:21:15.000", TimeScalesFactory.getUTC());
// one line sensor
// position: 1.5m in front (+X) and 20 cm above (-Z) of the S/C center of mass
// los: swath in the (YZ) plane, centered at +Z, ±10° aperture, 960 pixels
Vector3D position = new Vector3D(1.5, 0, -0.2);
TimeDependentLOS los = TestUtils.createLOSPerfectLine(Vector3D.PLUS_K, Vector3D.PLUS_I,
FastMath.toRadians(10.0), dimension).build();
// linear datation model: at reference time we get line 200, and the rate is one line every 1.5ms
LineDatation lineDatation = new LinearLineDatation(crossing, dimension / 2, 1.0 / 1.5e-3);
int firstLine = 0;
int lastLine = dimension;
LineSensor lineSensor = new LineSensor("line", lineDatation, position, los);
AbsoluteDate minDate = lineSensor.getDate(firstLine);
AbsoluteDate maxDate = lineSensor.getDate(lastLine);
RuggedBuilder builder = new RuggedBuilder().
setAlgorithm(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID).
setEllipsoid(EllipsoidId.IERS2003, BodyRotatingFrameId.ITRF).
setTimeSpan(minDate, maxDate, 0.001, 5.0).
setTrajectory(InertialFrameId.EME2000,
TestUtils.orbitToPV(orbit, earth, minDate.shiftedBy(-1.0), maxDate.shiftedBy(+1.0), 0.25),
8, CartesianDerivativesFilter.USE_PV,
TestUtils.orbitToQ(orbit, earth, minDate.shiftedBy(-1.0), maxDate.shiftedBy(+1.0), 0.25),
2, AngularDerivativesFilter.USE_R).
addLineSensor(lineSensor);
Rugged rugged = builder.build();
// Check builder
assertTrue(builder.getName().equalsIgnoreCase("Rugged"));
// Check a date in the range of minDate - maxDate
AbsoluteDate midddleDate = lineSensor.getDate((firstLine+lastLine)/2.);
assertTrue(rugged.isInRange(midddleDate));
// Get the algorithm
assertTrue(rugged.getAlgorithm().getClass().isInstance(new IgnoreDEMAlgorithm()));
// Get the algorithm Id
assertEquals(AlgorithmId.IGNORE_DEM_USE_ELLIPSOID, rugged.getAlgorithmId());
// Change the min and max line in inverse location to update the SensorMeanPlaneCrossing when the planeCrossing is not null
int minLine = firstLine;
int maxLine = lastLine;
double line = (firstLine + lastLine)/2.;
double pixel = dimension/2.;
AbsoluteDate date = lineSensor.getDate(line);
Vector3D pixelLos = lineSensor.getLOS(date, pixel);
GeodeticPoint gp = rugged.directLocation(date, position, pixelLos);
SensorPixel sp = rugged.inverseLocation("line", gp, minLine, maxLine);
int minLineNew = minLine + 10;
int maxLineNew = maxLine - 10;
SensorPixel spChangeLines = rugged.inverseLocation("line", gp, minLineNew, maxLineNew);
assertEquals(sp.getPixelNumber(), spChangeLines.getPixelNumber(), 1.e-9);
assertEquals(sp.getLineNumber(), spChangeLines.getLineNumber(), 1.e-9);
// For computeInverseLocOnGridWithoutAtmosphere special cases
try {
java.lang.reflect.Method computeWithoutAtmosphere =
rugged.getClass().getDeclaredMethod("computeInverseLocOnGridWithoutAtmosphere",
GeodeticPoint[][].class,
Integer.TYPE, Integer.TYPE,
LineSensor.class, Integer.TYPE, Integer.TYPE);
computeWithoutAtmosphere.setAccessible(true);
final int nbPixelGrid = 2;
final int nbLineGrid = 2;
GeodeticPoint[][] groundGridWithAtmosphere = new GeodeticPoint[nbPixelGrid][nbLineGrid];
for (int i = 0; i < nbPixelGrid; i++) {
for (int j = 0; j < nbLineGrid; j++) {
groundGridWithAtmosphere[i][j] = null;
}
}
SensorPixel[][] spNull = (SensorPixel[][]) computeWithoutAtmosphere.invoke(rugged, groundGridWithAtmosphere, nbPixelGrid, nbLineGrid, lineSensor, minLine, maxLine);
for (int i = 0; i < nbPixelGrid; i++) {
for (int j = 0; j < nbLineGrid; j++) {
assertNull(spNull[i][j]);
}
}
} catch (NoSuchMethodException | SecurityException |
IllegalAccessException | IllegalArgumentException | InvocationTargetException e) {
Assert.fail(e.getLocalizedMessage());
}
}
@Before
public void setUp() throws URISyntaxException {
TestUtils.clearFactories();
}
}
/* 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,8 @@ import org.junit.Test;
import org.junit.rules.TemporaryFolder;
import org.orekit.bodies.BodyShape;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.data.DataProvidersManager;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.orbits.Orbit;
import org.orekit.rugged.TestUtils;
import org.orekit.rugged.api.AlgorithmId;
......@@ -63,7 +62,7 @@ public class DumpManagerTest {
public TemporaryFolder tempFolder = new TemporaryFolder();
@Test
public void testDump() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDump() throws URISyntaxException, IOException {
File dump = tempFolder.newFile();
DumpManager.activate(dump);
......@@ -146,12 +145,12 @@ public class DumpManagerTest {
}
public void variousRuggedCalls()
throws RuggedException, OrekitException, URISyntaxException {
throws URISyntaxException {
int dimension = 200;
String path = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(path)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(path)));
final BodyShape earth = TestUtils.createEarth();
final Orbit orbit = TestUtils.createOrbit(Constants.EIGEN5C_EARTH_MU);
......@@ -209,7 +208,7 @@ public class DumpManagerTest {
}
@Test
public void testAlreadyActive() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testAlreadyActive() throws URISyntaxException, IOException {
DumpManager.activate(tempFolder.newFile());
try {
......@@ -223,7 +222,7 @@ public class DumpManagerTest {
}
@Test
public void testNotActive() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testNotActive() throws URISyntaxException, IOException {
try {
DumpManager.deactivate();
Assert.fail("an exception should have been thrown");
......@@ -233,11 +232,9 @@ public class DumpManagerTest {
}
@Test
public void testWriteError() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testWriteError() throws URISyntaxException, IOException {
try {
File dump = tempFolder.newFile();
dump.setReadOnly();
DumpManager.activate(dump);
DumpManager.activate(tempFolder.getRoot());
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.DEBUG_DUMP_ACTIVATION_ERROR, re.getSpecifier());
......
/* 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,26 +17,46 @@
package org.orekit.rugged.errors;
import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertTrue;
import java.io.BufferedReader;
import java.io.BufferedWriter;
import java.io.File;
import java.io.FileInputStream;
import java.io.FileOutputStream;
import java.io.FileReader;
import java.io.IOException;
import java.io.InputStreamReader;
import java.io.OutputStreamWriter;
import java.io.PrintWriter;
import java.lang.reflect.Constructor;
import java.lang.reflect.InvocationTargetException;
import java.lang.reflect.Method;
import java.net.URISyntaxException;
import java.nio.charset.StandardCharsets;
import java.util.ArrayList;
import java.util.List;
import java.util.Locale;
import org.hipparchus.analysis.differentiation.DSFactory;
import org.hipparchus.analysis.differentiation.DerivativeStructure;
import org.hipparchus.geometry.euclidean.threed.FieldVector3D;
import org.hipparchus.geometry.euclidean.threed.Vector3D;
import org.junit.Assert;
import org.junit.Rule;
import org.junit.Test;
import org.junit.rules.TemporaryFolder;
import org.orekit.bodies.GeodeticPoint;
import org.orekit.data.DataProvidersManager;
import org.orekit.data.DataContext;
import org.orekit.data.DirectoryCrawler;
import org.orekit.errors.OrekitException;
import org.orekit.rugged.api.Rugged;
import org.orekit.rugged.linesensor.SensorPixel;
import org.orekit.rugged.refraction.MultiLayerModel;
import org.orekit.rugged.utils.DerivativeGenerator;
import org.orekit.time.AbsoluteDate;
import org.orekit.time.TimeScalesFactory;
import org.orekit.utils.ParameterDriver;
public class DumpReplayerTest {
......@@ -44,10 +64,10 @@ public class DumpReplayerTest {
public TemporaryFolder tempFolder = new TemporaryFolder();
@Test
public void testDirectLoc01() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDirectLoc01() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-01.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -67,10 +87,10 @@ public class DumpReplayerTest {
}
@Test
public void testDirectLoc02() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDirectLoc02() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-02.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -90,10 +110,10 @@ public class DumpReplayerTest {
}
@Test
public void testDirectLoc03() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDirectLoc03() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-03.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -113,10 +133,10 @@ public class DumpReplayerTest {
}
@Test
public void testDirectLoc04() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDirectLoc04() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-04.txt").toURI().getPath();
File dump = tempFolder.newFile();
......@@ -144,10 +164,37 @@ public class DumpReplayerTest {
}
@Test
public void testInverseLoc01() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testDirectLocNull() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// Create a dump file with NULL result for direct location
createDataForCreateRugged(bw);
bw.write("direct location: date 2012-01-01T12:29:30.85Z position 0.0e+00 0.0e+00 0.0e+00 " +
"los -2.2e-02 -9.1e-02 9.9e-01 lightTime false aberration false refraction false");
bw.newLine();
bw.write("direct location result: NULL");
}
DumpReplayer replayer = new DumpReplayer();
replayer.parse(tempFile);
Rugged rugged = replayer.createRugged();
DumpReplayer.Result[] results = replayer.execute(rugged);
assertTrue(results[0].getExpected() == null);
tempFile.delete();
}
@Test
public void testInverseLoc01() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-inverse-loc-01.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -166,10 +213,10 @@ public class DumpReplayerTest {
}
@Test
public void testInverseLoc02() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testInverseLoc02() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-inverse-loc-02.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -188,10 +235,10 @@ public class DumpReplayerTest {
}
@Test
public void testInverseLoc03() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testInverseLoc03() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-inverse-loc-03.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
......@@ -208,20 +255,45 @@ public class DumpReplayerTest {
}
}
@Test
public void testCorruptedFiles() throws URISyntaxException, IOException, OrekitException, RuggedException {
public void testInverseLocNull() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataProvidersManager.getInstance().addProvider(new DirectoryCrawler(new File(orekitPath)));
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// Create a dump file with NULL result for inverse location
createDataForInvLocResult(bw);
bw.write("inverse location result: NULL");
}
DumpReplayer replayer = new DumpReplayer();
replayer.parse(tempFile);
Rugged rugged = replayer.createRugged();
DumpReplayer.Result[] results = replayer.execute(rugged);
assertTrue(results[0].getExpected() == null);
tempFile.delete();
}
@Test
public void testCorruptedFiles() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File folder = new File(getClass().getClassLoader().getResource("replay/replay-direct-loc-01.txt").toURI().getPath()).getParentFile();
for (final File file : folder.listFiles()) {
// split all data lines into fields
final List<String[]> lines = new ArrayList<>();
try (FileReader fr = new FileReader(file);
BufferedReader br = new BufferedReader(fr)) {
try (FileInputStream fis = new FileInputStream(file);
InputStreamReader isr = new InputStreamReader(fis, "UTF-8");
BufferedReader br = new BufferedReader(isr)) {
br.lines().
filter(line -> {
String trimmed = line.trim();
......@@ -233,8 +305,8 @@ public class DumpReplayerTest {
// for each field of each line, delete the field and check parsing fails
for (int i = 0; i < lines.size(); ++i) {
for (int j = 0; j < lines.get(i).length; ++j) {
File corrupted = tempFolder.newFile();
try (PrintWriter pw = new PrintWriter(corrupted)) {
final File corrupted = tempFolder.newFile();
try (PrintWriter pw = new PrintWriter(corrupted, "UTF-8")) {
for (int k = 0; k < lines.size(); ++k) {
for (int l = 0; l < lines.get(k).length; ++l) {
if (k != i || l != j) {
......@@ -253,10 +325,393 @@ public class DumpReplayerTest {
Assert.assertEquals(i + 1, ((Integer) re.getParts()[0]).intValue());
Assert.assertEquals(corrupted, re.getParts()[1]);
}
corrupted.delete();
}
}
}
}
@Test
public void testDirectLocIssue376_01() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-Issue376-01.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
replayer.parse(new File(dumpPath));
Rugged rugged = replayer.createRugged();
DumpReplayer.Result[] results = replayer.execute(rugged);
GeodeticPoint expectedGP = (GeodeticPoint) results[0].getExpected();
GeodeticPoint replayedGP = (GeodeticPoint) results[0].getReplayed();
double distance = Vector3D.distance(rugged.getEllipsoid().transform(expectedGP),
rugged.getEllipsoid().transform(replayedGP));
Assert.assertEquals(0.0, distance, 1.0e-8);
}
@Test
public void testDirectLocIssue376_02() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-Issue376-02.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
replayer.parse(new File(dumpPath));
Rugged rugged = replayer.createRugged();
DumpReplayer.Result[] results = replayer.execute(rugged);
GeodeticPoint expectedGP = (GeodeticPoint) results[0].getExpected();
GeodeticPoint replayedGP = (GeodeticPoint) results[0].getReplayed();
double distance = Vector3D.distance(rugged.getEllipsoid().transform(expectedGP),
rugged.getEllipsoid().transform(replayedGP));
Assert.assertEquals(0.0, distance, 1.0e-8);
}
@Test
public void testDirectLocIssue376_03() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
String dumpPath = getClass().getClassLoader().getResource("replay/replay-direct-loc-Issue376-03.txt").toURI().getPath();
DumpReplayer replayer = new DumpReplayer();
replayer.parse(new File(dumpPath));
Rugged rugged = replayer.createRugged();
DumpReplayer.Result[] results = replayer.execute(rugged);
for (int i= 0; i < results.length; i++) {
GeodeticPoint expectedGP = (GeodeticPoint) results[i].getExpected();
GeodeticPoint replayedGP = (GeodeticPoint) results[i].getReplayed();
double distance = Vector3D.distance(rugged.getEllipsoid().transform(expectedGP),
rugged.getEllipsoid().transform(replayedGP));
Assert.assertEquals(0.0, distance, 5.0e-8);
}
}
@Test
public void testCreateRuggedWithAtmosphere() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// CreateRugged with atmospheric refraction
bw.write("direct location: date 2012-01-01T12:30:00.0Z position 1.5e+00 0.e+00 -2.e-01 "+
"los 0.e+00 -7.5e-01 6.5e-01 lightTime true aberration true refraction true");
bw.newLine();
createDataForCreateRugged(bw);
}
DumpReplayer replayer = new DumpReplayer();
replayer.parse(tempFile);
Rugged rugged = replayer.createRugged();
assertTrue(rugged.getRefractionCorrection().getClass().isInstance(new MultiLayerModel(rugged.getEllipsoid())));
tempFile.delete();
}
@Test
public void testCreateRuggedNoDEMdata() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// CreateRugged with atmospheric refraction
bw.write("direct location: date 2012-01-01T12:30:00.0Z position 1.5e+00 0.e+00 -2.e-01 "+
"los 0.e+00 -7.5e-01 6.5e-01 lightTime true aberration true refraction false");
bw.newLine();
createDataForCreateRugged(bw);
bw.write("algorithm: DUVENHAGE");
}
DumpReplayer replayer = new DumpReplayer();
replayer.parse(tempFile);
Rugged rugged = replayer.createRugged();
try {
replayer.execute(rugged);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
// as the execution stops in the TilesCache: one must reset the DumpManager state
DumpManager.endNicely();
Assert.assertEquals(RuggedMessages.NO_DEM_DATA, re.getSpecifier());
}
tempFile.delete();
}
@Test
public void testLineParserBadKey() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// this empty line to ensure coverage
bw.write("");
bw.newLine();
// LineParser.parse: case bad key
bw.write("dummy : dummy");
}
DumpReplayer replayer = new DumpReplayer();
try {
replayer.parse(tempFile);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.CANNOT_PARSE_LINE, re.getSpecifier());
Assert.assertEquals(2, ((Integer) re.getParts()[0]).intValue());
Assert.assertEquals(tempFile, re.getParts()[1]);
Assert.assertTrue(re.getParts()[2].toString().contains("dummy : dummy"));
}
tempFile.delete();
}
@Test
public void testLineParserEndColon() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// LineParser.parse: case colon at end of line
bw.write("direct location result:");
}
DumpReplayer replayer = new DumpReplayer();
try {
replayer.parse(tempFile);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.CANNOT_PARSE_LINE, re.getSpecifier());
Assert.assertEquals(1, ((Integer) re.getParts()[0]).intValue());
Assert.assertEquals(tempFile, re.getParts()[1]);
}
tempFile.delete();
}
@Test
public void testLineParserNoColon() throws URISyntaxException, IOException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
File tempFile = tempFolder.newFile();
try (FileOutputStream fos = new FileOutputStream(tempFile);
OutputStreamWriter osw = new OutputStreamWriter(fos, StandardCharsets.UTF_8);
BufferedWriter bw = new BufferedWriter(osw)) {
// LineParser.parse case no colon
bw.write("sensorName s0 nbPixels 200 position 1.5e+00 0.0e+00 -2.0e-01");
}
DumpReplayer replayer = new DumpReplayer();
try {
replayer.parse(tempFile);
Assert.fail("an exception should have been thrown");
} catch (RuggedException re) {
Assert.assertEquals(RuggedMessages.CANNOT_PARSE_LINE, re.getSpecifier());
Assert.assertEquals(1, ((Integer) re.getParts()[0]).intValue());
Assert.assertEquals(tempFile, re.getParts()[1]);
}
tempFile.delete();
}
@Test
public void testParsedSensorGetDateGetLineCoverage() throws URISyntaxException, ClassNotFoundException, InstantiationException,
IllegalAccessException, IllegalArgumentException,
InvocationTargetException, NoSuchMethodException, SecurityException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
// ParsedSensor inner class
Class<?> innerClass = Class.forName("org.orekit.rugged.errors.DumpReplayer$ParsedSensor");
Constructor<?>[] constructors = innerClass.getDeclaredConstructors();
constructors[0].setAccessible(true);
Object parsedSensor = constructors[0].newInstance("dummy");
Method getLine = innerClass.getDeclaredMethod("getLine", AbsoluteDate.class);
getLine.setAccessible(true);
Method getDate = innerClass.getDeclaredMethod("getDate", double.class);
getDate.setAccessible(true);
Method setDatation = innerClass.getDeclaredMethod("setDatation", double.class, AbsoluteDate.class);
setDatation.setAccessible(true);
// datation with only one data
AbsoluteDate date0 = new AbsoluteDate("2012-01-06T02:27:16.139", TimeScalesFactory.getUTC());
setDatation.invoke(parsedSensor, 100., date0);
AbsoluteDate date = date0.shiftedBy(5.);
double foundLine = (double) getLine.invoke(parsedSensor, date);
assertEquals(100., foundLine, 1.e-15);
double line = 105.;
AbsoluteDate foundDate = (AbsoluteDate) getDate.invoke(parsedSensor, line);
assertEquals("2012-01-06T02:27:16.139",foundDate.toString(TimeScalesFactory.getUTC()));
// add datations data
AbsoluteDate date1 = date0.shiftedBy(10.);
AbsoluteDate date2 = date1.shiftedBy(10.);
setDatation.invoke(parsedSensor, 120., date1);
setDatation.invoke(parsedSensor, 150., date2);
foundLine = (double) getLine.invoke(parsedSensor, date);
assertEquals(110., foundLine, 1.e-15);
date = date2.shiftedBy(5.);
foundLine = (double) getLine.invoke(parsedSensor, date);
assertEquals(165., foundLine, 1.e-15);
date = date0.shiftedBy(-5.);
foundLine = (double) getLine.invoke(parsedSensor, date);
assertEquals(90., foundLine, 1.e-15);
}
@Test
public void testParsedSensorGetLOSCoverage() throws URISyntaxException, ClassNotFoundException, InstantiationException,
IllegalAccessException, IllegalArgumentException,
InvocationTargetException, NoSuchMethodException, SecurityException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
// ParsedSensor inner class
Class<?> innerClass = Class.forName("org.orekit.rugged.errors.DumpReplayer$ParsedSensor");
Constructor<?>[] constructors = innerClass.getDeclaredConstructors();
constructors[0].setAccessible(true);
Object parsedSensor = constructors[0].newInstance("dummy");
AbsoluteDate date = new AbsoluteDate("2012-01-06T02:27:16.139", TimeScalesFactory.getUTC());
// ParsedSensor.getLOS RunTimeException
Method getLos = innerClass.getDeclaredMethod("getLOS", int.class, AbsoluteDate.class);
getLos.setAccessible(true);
try {
getLos.invoke(parsedSensor, 1, date);
Assert.fail("an exception should have been thrown");
} catch (InvocationTargetException ite) {
RuggedInternalError rie = (RuggedInternalError) ite.getTargetException();
assertEquals(RuggedMessages.INTERNAL_ERROR, rie.getSpecifier());
assertEquals("https://gitlab.orekit.org/orekit/rugged/issues", rie.getParts()[0]);
assertTrue(rie.getMessage(Locale.FRENCH).startsWith("erreur interne"));
}
}
@Test
public void testParsedSensorLOSCoverage() throws URISyntaxException, ClassNotFoundException, InstantiationException,
IllegalAccessException, IllegalArgumentException,
InvocationTargetException, NoSuchMethodException, SecurityException {
String orekitPath = getClass().getClassLoader().getResource("orekit-data").toURI().getPath();
DataContext.getDefault().getDataProvidersManager().addProvider(new DirectoryCrawler(new File(orekitPath)));
// ParsedSensor inner class
Class<?> innerClass = Class.forName("org.orekit.rugged.errors.DumpReplayer$ParsedSensor");
Constructor<?>[] constructors = innerClass.getDeclaredConstructors();
constructors[0].setAccessible(true);
Object parsedSensor = constructors[0].newInstance("dummy");
AbsoluteDate date0 = new AbsoluteDate("2012-01-06T02:27:16.139", TimeScalesFactory.getUTC());
AbsoluteDate date = date0.shiftedBy(5.);
AbsoluteDate date1 = date0.shiftedBy(10.);
AbsoluteDate date2 = date1.shiftedBy(10.);
// ParsedSensor.setLos
Method setLos = innerClass.getDeclaredMethod("setLOS", AbsoluteDate.class, int.class, Vector3D.class);
setLos.setAccessible(true);
setLos.invoke(parsedSensor, date, 1, new Vector3D(0, 0, 0));
setLos.invoke(parsedSensor, date1, 100, new Vector3D(1, 1, 1));
setLos.invoke(parsedSensor, date2, 200, new Vector3D(2, 2, 2));
setLos.invoke(parsedSensor, date2.shiftedBy(10.), 200, new Vector3D(3, 3, 3));
// ParsedSensor.getLOSDerivatives
// Needs some LOS to be set
Method getLOSDerivatives = innerClass.getDeclaredMethod("getLOSDerivatives", int.class, AbsoluteDate.class, DerivativeGenerator.class);
getLOSDerivatives.setAccessible(true);
final DSFactory factory = new DSFactory(1, 1);
DerivativeGenerator<DerivativeStructure> generator = new DerivativeGenerator<DerivativeStructure>() {
@Override
public List<ParameterDriver> getSelected() {
return null;
}
@Override
public DerivativeStructure constant(final double value) {
return factory.constant(value);
}
@Override
public DerivativeStructure variable(final ParameterDriver driver) {
return null;
}
};
@SuppressWarnings("unchecked")
FieldVector3D<DerivativeStructure> fv= (FieldVector3D<DerivativeStructure>) getLOSDerivatives.invoke(parsedSensor, 1, date, generator);
assertEquals(0., fv.getX().getValue(), 1.e-15);
assertEquals(0., fv.getY().getValue(), 1.e-15);
assertEquals(0., fv.getZ().getValue(), 1.e-15);
// ParsedSensor.getParametersDrivers
Method getParametersDrivers = innerClass.getDeclaredMethod("getParametersDrivers");
getParametersDrivers.setAccessible(true);
getParametersDrivers.invoke(parsedSensor);
}
private void createDataForCreateRugged(BufferedWriter bw) throws IOException {
bw.write("ellipsoid: ae 6.378137e+06 f 3.35e-03 frame ITRF_CIO_CONV_2010_SIMPLE_EOP");
bw.newLine();
bw.write("span: minDate 2012-01-01T12:29:00.85Z maxDate 2012-01-01T12:30:00.15Z " +
"tStep 1.e-03 tolerance 5.e+00 inertialFrame EME2000");
bw.newLine();
bw.write("transform: index 150 body r -8.0e-01 -3.4e-04 4.8e-04 -5.8e-01 Ω -8.7e-08 1.2e-09 -7.3e-05 " +
"ΩDot -1.6e-16 8.9e-17 1.9e-19 spacecraft p 1.3e+04 3.1e+03 -7.1e+06 v -3.1e+01 -8.0e+00 8.2e+00 " +
"a -9.3e-01 -8.3e+00 1.3e-03 r -6.8e-01 4.1e-01 -3.8e-01 4.6e-01 Ω -1.e-03 1.9e-04 1.6e-04 " +
"ΩDot -3.6e-07 2.0e-07 -1.2e-06");
bw.newLine();
}
private void createDataForInvLocResult(BufferedWriter bw) throws IOException {
bw.write("inverse location: sensorName s0 latitude 1.4e+00 longitude -8.8e-01 elevation 3.1e+01 minLine -23040 maxLine 39851 " +
"lightTime false aberration false refraction false");
bw.newLine();
bw.write("ellipsoid: ae 6.378e+06 f 3.35e-03 frame ITRF_CIO_CONV_2010_SIMPLE_EOP");
bw.newLine();
bw.write("span: minDate 2015-07-07T18:38:55.0Z maxDate 2015-07-07T18:40:35.8Z tStep 1.e-01 tolerance 1.e+01 inertialFrame EME2000");
bw.newLine();
bw.write("transform: index 516 body r -2.2e-01 -7.3e-04 1.8e-04 -9.7e-01 Ω -1.1e-07 3.6e-09 -7.2e-05 " +
"ΩDot 0. 0. 0. spacecraft p -3.6e+02 -4.2e+02 -7.1e+06 v -7.4e+01 -3.4e+02 -1.8e-01 " +
"a 0. 0. 0. r -6.2e-02 7.4e-01 6.5e-01 4.1e-02 Ω 0. 0. 0. " +
"ΩDot 0. 0. 0.");
bw.newLine();
bw.write("sensor: sensorName s0 nbPixels 2552 position 0. 0. 0.");
bw.newLine();
bw.write("sensor mean plane: sensorName s0 minLine -23040 maxLine 39851 maxEval 50 accuracy 1.e-02 " +
"normal 9.e-01 -2.6e-02 1.8e-02 cachedResults 1 lineNumber 2.4e+04 date 2015-07-07T18:40:12.4Z " +
"target 5.8e+05 -7.1e+05 6.2e+06 targetDirection -1.5e-02 8.9e-02 9.9e-01 -2.0e-07 2.1e-08 -2.0e-07");
bw.newLine();
bw.write("sensor datation: sensorName s0 lineNumber 8.4e+03 date 2015-07-07T18:39:46.5Z");
bw.newLine();
bw.write("sensor rate: sensorName s0 lineNumber 2.4e+04 rate 6.3e+02");
bw.newLine();
}
}