Complete OD using ITRF

Hi Orekit community!

I’m completly new to Orekit and have absolutely no experience in Java which is not helping. I’m dealing with a problem: I want to make a pipeline that given input as position and velocity vectors in ITRF will firstly make IOD and then fit this IOD to the rest of positions to construct orbit. So far I have encountered numerous obstacles and I can’t really wrap my head around them.

First I have tried using iod_gibbs for my initial orbit determination but it gave me this error:

JavaError: <super: <class 'JavaError'>, <JavaError object>>
    Java stacktrace:
org.orekit.errors.OrekitIllegalArgumentException: non pseudo-inertial frame "CIO/2010-based ITRF accurate EOP"
	at org.orekit.orbits.Orbit.ensurePseudoInertialFrame(Orbit.java:202)
	at org.orekit.orbits.Orbit.<init>(Orbit.java:141)
	at org.orekit.orbits.KeplerianOrbit.<init>(KeplerianOrbit.java:313)
	at org.orekit.orbits.KeplerianOrbit.<init>(KeplerianOrbit.java:291)
	at org.orekit.orbits.KeplerianOrbit.<init>(KeplerianOrbit.java:422)
	at org.orekit.estimation.iod.IodGibbs.estimate(IodGibbs.java:143)
	at org.orekit.estimation.iod.IodGibbs.estimate(IodGibbs.java:86)

I’ve infered that I need to use other, pseudo-inertial frame. Is there a way to estimate IOD using ITRF?

Second, I have transformed three vectors to GCRF and IOD was created, albeit very inaccurate:

import math
i = math.ceil(len(dane.index) / 3)
points_for_iod = data.iloc[::i, :]
display(points_for_iod)


from org.hipparchus.geometry.euclidean.threed import Vector3D
from orekit.pyhelpers import datetime_to_absolutedate
from org.orekit.utils import PVCoordinates
from org.orekit.estimation.measurements import PV
pos_1 = points_for_iod.iloc[0]
p_vector_1 = Vector3D(pos_1[['x_', 'y_', 'z_']].to_list())
v_vector_1 = Vector3D(pos_1[["vx_", "vy_", "vz_"]].to_list())
date_1 = datetime_to_absolutedate(points_for_iod.index[0])
tmp_pv1 = PVCoordinates(p_vector_1, v_vector_1)
pv1 = itrf.getTransformTo(gcrf, date_1).transformPVCoordinates(tmp_pv1)

pos_2 = points_for_iod.iloc[1]
p_vector_2 = Vector3D(pos_2[['x_', 'y_', 'z_']].to_list())
v_vector_2 = Vector3D(pos_2[["vx_", "vy_", "vz_"]].to_list())
date_2 = datetime_to_absolutedate(points_for_iod.index[1])
tmp_pv2 = PVCoordinates(p_vector_2, v_vector_2)
pv2 = itrf.getTransformTo(gcrf, date_2).transformPVCoordinates(tmp_pv2)

pos_3 = points_for_iod.iloc[2]
p_vector_3 = Vector3D(pos_3[['x_', 'y_', 'z_']].to_list())
v_vector_3 = Vector3D(pos_3[["vx_", "vy_", "vz_"]].to_list())
date_3 = datetime_to_absolutedate(points_for_iod.index[2])
tmp_pv3 = PVCoordinates(p_vector_3, v_vector_3)
pv3 = itrf.getTransformTo(gcrf, date_3).transformPVCoordinates(tmp_pv3)

from org.orekit.estimation.iod import IodGibbs
from org.orekit.utils import Constants as orekit_constants
iod_gibbs = IodGibbs(orekit_constants.EIGEN5C_EARTH_MU)
initialOrbit = iod_gibbs.estimate(gcrf,
                                      pv1.getPosition(), date_1,
                                      pv2.getPosition(), date_2,
                                      pv3.getPosition(), date_3)

Next obstacle appeared when I tried to propagate this orbit:

prop_min_step = 0.001 # s
prop_max_step = 300.0 # s
prop_position_error = 5000.0 # m

estimator_position_scale = 1.0 # m
estimator_convergence_thres = 1e-2
estimator_max_iterations = 75
estimator_max_evaluations = 100

from org.orekit.propagation.conversion import DormandPrince853IntegratorBuilder
integratorBuilder = DormandPrince853IntegratorBuilder(prop_min_step, prop_max_step, prop_position_error)

from org.orekit.propagation.conversion import NumericalPropagatorBuilder
from org.orekit.orbits import PositionAngle
propagatorBuilder = NumericalPropagatorBuilder(initialOrbit,
                                               integratorBuilder,
                                               PositionAngle.TRUE,
                                               estimator_position_scale)

from org.hipparchus.linear import QRDecomposer
matrix_decomposer = QRDecomposer(1e-11)
from org.hipparchus.optim.nonlinear.vector.leastsquares import GaussNewtonOptimizer
optimizer = GaussNewtonOptimizer(matrix_decomposer, False)

from org.orekit.estimation.leastsquares import BatchLSEstimator
estimator = BatchLSEstimator(optimizer, propagatorBuilder)
estimator.setParametersConvergenceThreshold(estimator_convergence_thres)
estimator.setMaxIterations(estimator_max_iterations)
estimator.setMaxEvaluations(estimator_max_evaluations)

from org.orekit.estimation.measurements import Position, ObservableSatellite

observableSatellite = ObservableSatellite(0) # Propagator index = 0

for timestamp, pv_gcrf in data.iterrows():
    tmp_p = Vector3D(pv_gcrf[['x_', 'y_', 'z_']].to_list())
    tmp_v = Vector3D(pv_gcrf[['vx_', 'vy_', 'vz_']].to_list())
    tmp_pvc = PVCoordinates(tmp_p, tmp_v)
    pvc = itrf.getTransformTo(gcrf, datetime_to_absolutedate(timestamp)).transformPVCoordinates(tmp_pvc)
    orekit_position = Position(
        datetime_to_absolutedate(timestamp),
        pvc.getPosition(),
        1000.0,
        1.0,  # Base weight
        observableSatellite
    )
    estimator.addMeasurement(orekit_position)

estimatedPropagatorArray = estimator.estimate()

This resulted in error:

JavaError: <super: <class 'JavaError'>, <JavaError object>>
    Java stacktrace:
org.orekit.errors.OrekitException: Jacobian matrix for type KEPLERIAN is singular with current orbit
	at org.orekit.propagation.numerical.NumericalPropagator.tolerances(NumericalPropagator.java:1081)
	at org.orekit.propagation.numerical.NumericalPropagator.tolerances(NumericalPropagator.java:1025)
	at org.orekit.propagation.conversion.DormandPrince853IntegratorBuilder.buildIntegrator(DormandPrince853IntegratorBuilder.java:55)
	at org.orekit.propagation.conversion.NumericalPropagatorBuilder.buildPropagator(NumericalPropagatorBuilder.java:206)
	at org.orekit.propagation.conversion.NumericalPropagatorBuilder.buildPropagator(NumericalPropagatorBuilder.java:46)
	at org.orekit.estimation.leastsquares.AbstractBatchLSModel.createPropagators(AbstractBatchLSModel.java:419)
	at org.orekit.estimation.leastsquares.AbstractBatchLSModel.value(AbstractBatchLSModel.java:298)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresFactory$LocalLeastSquaresProblem.evaluate(LeastSquaresFactory.java:440)
	at org.orekit.estimation.leastsquares.BatchLSEstimator$TappedLSProblem.evaluate(BatchLSEstimator.java:615)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.GaussNewtonOptimizer.optimize(GaussNewtonOptimizer.java:163)
	at org.orekit.estimation.leastsquares.BatchLSEstimator.estimate(BatchLSEstimator.java:435)

I’ve found somewhere in this forum that you can work around this error by changing orbity type to cartesian. So I’ve changed the code:

initialCartOrbit = OrbitType.CARTESIAN.convertType(initialOrbit)
propagatorBuilder = NumericalPropagatorBuilder(initialCartOrbit,
                                               integratorBuilder,
                                               PositionAngle.TRUE,
                                               estimator_position_scale)

and it kinda worked. My last step was getting estimated Keplerian orbit:

dt = 1.0
date_start = datetime_to_absolutedate(dane.index[0])
date_end = datetime_to_absolutedate(dane.index[-1])


estimatedPropagator = estimatedPropagatorArray[0]
estimatedInitialState = estimatedPropagator.getInitialState()

orbit = OrbitType.KEPLERIAN.convertType(estimatedInitialState.getOrbit())

Using this I’ve gotten pretty accurate orbit. RAAN, e and i are pretty spot on, a is 3 km bigger then truth but that’s okay for now.

Last problems that I don’t know how to deal with is why I cant set ephmeris mode to this estimated propagator and why this orbit has no attributes like " getPerigeeArgument()" or “getRightAscensionOfAscendingNode()”

In summary, is there a better way of performing IOD and OD with ITRF data that I have? Maybe a way that has none of the problems mentioned above?

Hi @jlipinski,

Welcome to the Orekit community !

Currently I don’t think there is a way to use IODGibbs with a non inertial frame.
So converting your PV in ITRF to an inertial frame like GCRF is the proper way to do it.
I think it would be hard to write the IOD method so they can use non inertial frames. I’m not sure the time required to develop it would be worth it, since a simple frame conversion can do the trick.

Yes, or maybe circular orbit. What does your orbit look like, is it a circular orbit ?

Do you have any force model added to your propagatorBuilder. It doesn’t seem so from your code.
If so you are doing the propagation and the fitting of the orbit with a pure Keplerian model (only the point mass gravity of the Earth is taken into account).
Maybe you should add some force models if you want to have a better estimation of the orbit, like:

  • A gravity model with sufficiently high degree/order
  • The influence of the Sun and Moon as third bodies
  • The atmospheric drag (if your satellite is low enough)
  • The solar radiation pressure
    etc.

I think you need to cast the resulting orbit to KeplerianOrbit since the generic type Orbit doesn’t have the methods getPerigeeArgument and getRightAscensionOfAscendingNode.
See this recent answer from @bcazabonne for help on casting objects in Orekit Python.

setEphemerisMode doesn’t exist anymore in Orekit since 11.0.
The proper way to do it now is to do like in the Ephemeris Mode tutorial, that is (in Java):

// Before propagation: prepare the ephemeris generator
EphemerisGenerator generator = propagator.getEphemerisGenerator();

// Propagate
propagator.propagate(startDate, endDate)

// Get the generated ephemeris
BoundedPropagator ephemeris = generator.getGeneratedEphemeris()

I think you are going in the right direction.
Doing the OD in non-inertial frame is quite more complex and prone to error (in my opinion).
What you could do is design your own measurement class that would handle the conversion from ITRF to GCRF at construction, so you wouldn’t have to explicitly do it in your main code anymore .
But it would just be moving around some part of code from a place to another, so I don’t think that it is what you’re looking for.

Hope this helps,
Maxime

1 Like

Thank you very much @MaximeJ !

All of your suggestions worked! I have also added some force models, but TBH I didn’t notce any significant changes in estimated orbits (I’m working with LEO satellites with altitudes <1000km so I feel like I did something wrong).

Right now I’m dealing with another problem that I don’t know if it is easily resolvable. I’m working mainly with pretty short (but dense) arcs (for example I have ~100 measurments for 20 sec arc) and I don’t know if this is enough to estimate orbit with enough accuracy.

In my data I’ve found one satellite that I have observations of in 2 consecutive nights. So I performed OD on measurments from first night and propagated it to the next night. Unfortunately results from my propagation are way off compared to measurments:

Red dots are measurments used for orbit determination (blue lines). Green dots are measurments from next night, purple dots are calculated positions for next night.

Code that im working on:

from org.orekit.frames import FramesFactory
from org.orekit.utils import IERSConventions
gcrf = FramesFactory.getGCRF()
itrf = FramesFactory.getITRF(IERSConventions.IERS_2010, False)

from org.orekit.time import TimeScalesFactory
utc = TimeScalesFactory.getUTC()

from org.orekit.models.earth import ReferenceEllipsoid
wgs84Ellipsoid = ReferenceEllipsoid.getWgs84(itrf)
from org.orekit.bodies import CelestialBodyFactory
moon = CelestialBodyFactory.getMoon()
sun = CelestialBodyFactory.getSun()

Transforming data from itrf to gcrf (I feel like there is more efficient and pythonic way):

from org.orekit.estimation.measurements import Position

import math
i = math.ceil(len(dane.index) / 2)
points_for_iod = dane.iloc[[0, i, -1]]

from org.hipparchus.geometry.euclidean.threed import Vector3D
from orekit.pyhelpers import datetime_to_absolutedate
from org.orekit.utils import PVCoordinates

pos_1 = points_for_iod.iloc[0]
p_vector_1 = Vector3D(pos_1[['x_', 'y_', 'z_']].to_list())
v_vector_1 = Vector3D(pos_1[["vx_", "vy_", "vz_"]].to_list())
date_1 = datetime_to_absolutedate(points_for_iod.index[0])
tmp_pv1 = PVCoordinates(p_vector_1, v_vector_1)
pv1 = itrf.getTransformTo(gcrf, date_1).transformPVCoordinates(tmp_pv1)

pos_2 = points_for_iod.iloc[1]
p_vector_2 = Vector3D(pos_2[['x_', 'y_', 'z_']].to_list())
v_vector_2 = Vector3D(pos_2[["vx_", "vy_", "vz_"]].to_list())
date_2 = datetime_to_absolutedate(points_for_iod.index[1])
tmp_pv2 = PVCoordinates(p_vector_2, v_vector_2)
pv2 = itrf.getTransformTo(gcrf, date_2).transformPVCoordinates(tmp_pv2)

pos_3 = points_for_iod.iloc[2]
p_vector_3 = Vector3D(pos_3[['x_', 'y_', 'z_']].to_list())
v_vector_3 = Vector3D(pos_3[["vx_", "vy_", "vz_"]].to_list())
date_3 = datetime_to_absolutedate(points_for_iod.index[2])
tmp_pv3 = PVCoordinates(p_vector_3, v_vector_3)
pv3 = itrf.getTransformTo(gcrf, date_3).transformPVCoordinates(tmp_pv3)

Performing IOD:

from org.orekit.estimation.iod import IodGibbs
from org.orekit.utils import Constants as orekit_constants
iod_gibbs = IodGibbs(orekit_constants.EIGEN5C_EARTH_MU)
initialOrbit = iod_gibbs.estimate(gcrf,
                                      pv1.getPosition(), date_1,
                                      pv2.getPosition(), date_2,
                                      pv3.getPosition(), date_3)
display(initialOrbit)

#<KeplerianOrbit: Keplerian parameters: {a: 5665948.126048018; e: 0.2763193273172972; i: 81.17959707499644; pa: -44.55326269968; raan: 119.82447080790052; v: 178.94313046625413;}>

Setting up estimator and propagator:

# Estimator parameters
estimator_position_scale = 1.0 # m
estimator_convergence_thres = 1e-2
estimator_max_iterations = 25
estimator_max_evaluations = 35

# Orbit propagator parameters
prop_min_step = 0.001 # s
prop_max_step = 300.0 # s
prop_position_error = 10.0 # m

from org.orekit.propagation.conversion import DormandPrince853IntegratorBuilder
integratorBuilder = DormandPrince853IntegratorBuilder(prop_min_step, prop_max_step, prop_position_error)

from org.orekit.propagation.conversion import NumericalPropagatorBuilder
from org.orekit.orbits import PositionAngle, OrbitType
initialCartOrbit = OrbitType.CARTESIAN.convertType(initialOrbit)
propagatorBuilder = NumericalPropagatorBuilder(initialCartOrbit,
                                               integratorBuilder,
                                               PositionAngle.TRUE,
                                               estimator_position_scale)

from org.orekit.forces.gravity.potential import GravityFieldFactory
gravityProvider = GravityFieldFactory.getConstantNormalizedProvider(64, 64)
from org.orekit.forces.gravity import HolmesFeatherstoneAttractionModel
gravityAttractionModel = HolmesFeatherstoneAttractionModel(itrf, gravityProvider)
propagatorBuilder.addForceModel(gravityAttractionModel)

from org.orekit.forces.gravity import ThirdBodyAttraction
moon_3dbodyattraction = ThirdBodyAttraction(moon)
propagatorBuilder.addForceModel(moon_3dbodyattraction)
sun_3dbodyattraction = ThirdBodyAttraction(sun)
propagatorBuilder.addForceModel(sun_3dbodyattraction)

from org.orekit.forces.radiation import IsotropicRadiationSingleCoefficient
isotropicRadiationSingleCoeff = IsotropicRadiationSingleCoefficient(100.0, 1.0);
from org.orekit.forces.radiation import SolarRadiationPressure
solarRadiationPressure = SolarRadiationPressure(sun, wgs84Ellipsoid.getEquatorialRadius(),
                                                isotropicRadiationSingleCoeff)
propagatorBuilder.addForceModel(solarRadiationPressure)

from org.orekit.models.earth.atmosphere.data import MarshallSolarActivityFutureEstimation
from orekit import JArray
msafe = MarshallSolarActivityFutureEstimation(
    '(?:jan|feb|mar|apr|may|jun|jul|aug|sep|oct|nov|dec)\p{Digit}\p{Digit}\p{Digit}\p{Digit}f10\.(?:txt|TXT)', 
    MarshallSolarActivityFutureEstimation.StrengthLevel.AVERAGE)

DM.feed(msafe.getSupportedNames(), msafe)

from org.orekit.models.earth.atmosphere import NRLMSISE00
atmosphere = NRLMSISE00(msafe, sun, wgs84Ellipsoid)

from org.orekit.forces.drag import IsotropicDrag
isotropicDrag = IsotropicDrag(100.0, 1.0)

from org.orekit.forces.drag import DragForce
dragForce = DragForce(atmosphere, isotropicDrag)
propagatorBuilder.addForceModel(dragForce)

from org.hipparchus.linear import QRDecomposer
matrix_decomposer = QRDecomposer(1e-11)
from org.hipparchus.optim.nonlinear.vector.leastsquares import GaussNewtonOptimizer
optimizer = GaussNewtonOptimizer(matrix_decomposer, False)

from org.orekit.estimation.leastsquares import BatchLSEstimator
estimator = BatchLSEstimator(optimizer, propagatorBuilder)
estimator.setParametersConvergenceThreshold(estimator_convergence_thres)
estimator.setMaxIterations(estimator_max_iterations)
estimator.setMaxEvaluations(estimator_max_evaluations)

Adding measurments to the estimator and estimating:

from org.orekit.estimation.measurements import Position, ObservableSatellite

observableSatellite = ObservableSatellite(0) # Propagator index = 0

for timestamp, pv_gcrf in dane.iterrows():
    tmp_p = Vector3D(pv_gcrf[['x_', 'y_', 'z_']].to_list())
    tmp_v = Vector3D(pv_gcrf[['vx_', 'vy_', 'vz_']].to_list())
    tmp_pvc = PVCoordinates(tmp_p, tmp_v)
    pvc = itrf.getTransformTo(gcrf, datetime_to_absolutedate(timestamp)).transformPVCoordinates(tmp_pvc)
    orekit_position = Position(
        datetime_to_absolutedate(timestamp),
        pvc.getPosition(),
        1000.0,
        1.0,  # Base weight
        observableSatellite
    )
    estimator.addMeasurement(orekit_position)

estimatedPropagatorArray = estimator.estimate()

Getting estimated orbit:

from org.orekit.orbits import KeplerianOrbit
estimatedPropagator = estimatedPropagatorArray[0]
estimatedInitialState = estimatedPropagator.getInitialState()
tmp_orbit = OrbitType.KEPLERIAN.convertType(estimatedInitialState.getOrbit())
orbit = KeplerianOrbit.cast_(tmp_orbit)
display(orbit)
#<KeplerianOrbit: Keplerian parameters: {a: 7129764.816986412; e: 0.01604576521836157; i: 81.19281051652376; pa: -18.340653585441842; raan: 119.8104073176335; v: 152.7333235809643;}>

Setting up bounded propagator:

dt = 60.0
date_start = datetime_to_absolutedate(dane.index[0])
date_end = datetime_to_absolutedate(dane.index[-1]).shiftedBy(86400.0)
ephmerisGenerator = estimatedPropagator.getEphemerisGenerator()
estimatedPropagator.propagate(date_start, date_end)
boundedPropagator = ephmerisGenerator.getGeneratedEphemeris()

Propagating to the next night, saving results to “pos_df”:

from orekit.pyhelpers import absolutedate_to_datetime
pos_df = pd.DataFrame(columns=['x', 'y', 'z', 'vx', 'vy', 'vz'])

date_current = date_start
while date_current.compareTo(date_end) <= 0:
    datetime_current = absolutedate_to_datetime(date_current)    
    spacecraftState = boundedPropagator.propagate(date_current)
    pv = spacecraftState.getPVCoordinates(itrf)
    pos = np.array(pv.getPosition().toArray())
    pos_df.loc[datetime_current] = np.concatenate(
        (pos,
         np.array(pv.getVelocity().toArray()))
        )
    date_current = date_current.shiftedBy(dt)    

Calculating next night position in roughy same times as my measurments (“dane2” is dataframe with measurments from the next night):

pos_df_next = pd.DataFrame(columns=['x', 'y', 'z', 'vx', 'vy', 'vz'])

date_start = datetime_to_absolutedate(dane2.index[0])
date_end = datetime_to_absolutedate(dane2.index[-1])
dt = 0.2
display(date_start, date_end)
date_current = date_start
while date_current.compareTo(date_end) <= 0:
    datetime_current = absolutedate_to_datetime(date_current)    
    spacecraftState = boundedPropagator.propagate(date_current)
    pv = spacecraftState.getPVCoordinates(itrf)
    pos = np.array(pv.getPosition().toArray())
    pos_df_next.loc[datetime_current] = np.concatenate(
        (pos,
         np.array(pv.getVelocity().toArray()))
        )
    date_current = date_current.shiftedBy(dt) 

Plotting (plot uploaded above code):

import plotly.graph_objects as go

fig_data = data=[    
    go.Scatter3d(x=pos_df['x'], y=pos_df['y'], z=pos_df['z'],
        mode='lines',
        name='Batch least squares solution'),
    go.Scatter3d(x=dane['x_'], y=dane['y_'], z=dane['z_'],
        mode='markers',
        name='Measurements'),
    go.Scatter3d(x=dane2['x_'], y=dane2['y_'], z=dane2['z_'],
        mode='markers',
        name='Measurements (next day)'),
    go.Scatter3d(x=pos_df_next['x'], y=pos_df_next['y'], z=pos_df_next['z'],
        mode='markers',
        name='Batch least squares solution (next day)'),
]
scene=dict(
    aspectmode='data',
)
layout = dict(
    scene=scene
)
fig = go.Figure(
    data=fig_data,
    layout=layout)
fig.show()

Is there something really wrong with this code or it’s just not possible to determine accurate enough orbit with such short arcs?

Hi @jlipinski,

You’re very welcome, I’m happy to help !

I don’t think so but I must admit I didn’t have time check all the details thoroughly and find a hidden bug.

I’m not sure I fully understand your plot but the propagated orbit seems to be wrong not only along track but also cross-track (i.e. the orbit plane is wrong after one day). I wouldn’t have expected that but it’s true that 20s is really a short arc.
Any idea on how far the propagated orbit is with respect to the measurements ?

It will be harder, that’s for sure, especially if the perturbation forces are strong, which is usually the case in LEO.
Solar radiation pressure and drag coefficients will definitely be un-observable on such short arcs.
But it doesn’t look like you are trying to estimate them in your code

Again, with a very short arc, additional force models won’t change the estimation much.
But they will change the one day propagation afterwards, and a lot!

I’ve seen that you’re using 100m² for the cross-section of SRP and drag, and 1 for the coefficients. This is a huge area and it seems to be a default number for the coefficients. Are you sure about these values ?

How high is your satellite ? Is it strongly subject to drag ?

Some suggestions to (maybe) improve the solution:

I tend to use maximum 60s for a LEO spacecraft (propagation will be slower though).

MSAFE is a really coarse model (monthly estimates) used mainly for mission analysis or future mission.
I suggest you use the CssiSpaceWeatherData model instead, it is based on real daily observations and performs much better.

Once again, these two look suspicious :wink:

If you have measurements on position and velocity you should use a PV measurements instead of a Position measurements.
Do you really have only 1km precision on the three axis of your position. This looks huge for a GNSS receiver; but if it’s the case, do not expect a good precision on the OD and even less after one day of propagation.

Last point, if your satellite is really low you should also try to add solid tides as perturbing forces.

Hope this will help you,
Maxime

1 Like

Hi @MaximeJ !
Thank you again for your amazing suggestions!

To be honest I just messed with them to see if they have any impact on OD and forgot to write correct values back. According to N2YO this satellite RCS is 4m2 so I used it as my cross-section and for coefficents I used values of 2.2 for drag coefficent and 1.0 for SRP coefficent.

Additionally I’ve changed prop_max_step to 60.0s, MSAFE to CssiSpaceWeatherData, I’ve added ocean and solid tides, and changed measurments to PV instead of Position. 1 km precision was also messed up number for the sake of checking its impact on OD.

I’ve also started using GCRF instead of ITRF for plots to make them clearer:

plotly_orbit.html (3.6 MB)

Unfortunately all of those changes made no difference, still there is huge gap between observed position and estimated.

Hi @jlipinski,

Hard to say without the real data.

Is your orekit-data folder up to date with your propagation span ? Here I mean mainly the EOP, Earth Orientation Parameters.

What are your the semi-major axis and eccentricity of your orbit ?

What you could try is to incorporate the second batch of measurements (those from “next day”) in your batch-LS OD and:

  • Check how your estimated orbit changes with that (measure the distance from previous solution in a local orbital frame for example, or compare the shapes of the orbit)
  • Do the propagation again and see how far you are from the second batch (if this works you should be close this time)
    This can rule out some modelling problems and would show that maybe the problem comes from a measurements’ arc that is too short.

Additionally, with this longer arc, you will be able to try to estimate the drag (and then eventually SRP) coefficients. That could also give you some hints on whether your dynamic is well-modeled or not.

Hope this helps,
Maxime

1 Like

Here you go:
ID7490.csv (44.9 KB)

There are no errors in the data though but camera used for observations has resolution of 10arcsec/px => 10arcsec is more or less 50m at 900 km, so I used 50m as my position error. Unfortunately I have no way of estimating velocity errors. In code I’m using 0.5m/s.
There is also possibility that those observations are completely wrong, sadly I have no way of knowing, I only have data containing times, satid and positions with no information about precision or quality of observations. Moreover the data that I shared above is the only case of satellite being observed 2 nights in a row, so I can’t test the propagation on any other satellite. Right now I’m hoping for better weather so I can get more data to work with.

Yes, I updated them 2 days ago (via update.sh).

<KeplerianOrbit: Keplerian parameters: {a: 7133062.823860537; e: 0.015607938149345819; i: 81.19714746329568; pa: -17.702739263612216; raan: 119.80616904434257; v: 152.11912495489463;}>

Out of curiosity I compared those parameters with ones calculated from current TLE for this satelite. Of course I compared only a, e and i as the rest changes quite fast and/or is really hard to estimate properly for low eccentricty orbits. Semi major axis differs a lot for this case, about 100km so yeah… observations may be completely wrong. So I checked the other way. I’ve performed IOD and OD using second batch and propagate it backward. Got a lot better orbit (compared to TLE):
<KeplerianOrbit: Keplerian parameters: {a: 7250993.557132661; e: 0.0031648945580124506; i: 81.38594336469274; pa: 162.74875049553592; raan: 118.64141111913628; v: -28.781316994025005;}>

Sadly propagated backwards results still differ a lot:

orb.html (3.6 MB)

Unfortunately, when I add measurements from 2nd batch to IOD calculated on 1st batch I got this error:

JavaError                                 Traceback (most recent call last)
Input In [36], in <cell line: 1>()
----> 1 estimatedPropagatorArray = estimator.estimate()

JavaError: <super: <class 'JavaError'>, <JavaError object>>
    Java stacktrace:
org.orekit.errors.OrekitException: trajectory inside the Brillouin sphere (r = 6 378 073,639)
	at org.orekit.forces.radiation.AbstractRadiationForceModel.getEclipseAngles(AbstractRadiationForceModel.java:133)
	at org.orekit.forces.radiation.SolarRadiationPressure.getLightingRatio(SolarRadiationPressure.java:175)
	at org.orekit.forces.radiation.SolarRadiationPressure.getTotalLightingRatio(SolarRadiationPressure.java:369)
	at org.orekit.forces.radiation.SolarRadiationPressure.acceleration(SolarRadiationPressure.java:127)
	at org.orekit.forces.ForceModel.addContribution(ForceModel.java:109)
	at org.orekit.propagation.numerical.NumericalPropagator$Main.computeDerivatives(NumericalPropagator.java:899)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator$ConvertedMainStateEquations.computeDerivatives(AbstractIntegratedPropagator.java:758)
	at org.hipparchus.ode.ExpandableODE.computeDerivatives(ExpandableODE.java:134)
	at org.hipparchus.ode.AbstractIntegrator.computeDerivatives(AbstractIntegrator.java:265)
	at org.hipparchus.ode.nonstiff.EmbeddedRungeKuttaIntegrator.integrate(EmbeddedRungeKuttaIntegrator.java:252)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator.integrateDynamics(AbstractIntegratedPropagator.java:477)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator.propagate(AbstractIntegratedPropagator.java:425)
	at org.orekit.propagation.PropagatorsParallelizer.propagate(PropagatorsParallelizer.java:140)
	at org.orekit.estimation.leastsquares.AbstractBatchLSModel.value(AbstractBatchLSModel.java:319)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresFactory$LocalLeastSquaresProblem.evaluate(LeastSquaresFactory.java:440)
	at org.orekit.estimation.leastsquares.BatchLSEstimator$TappedLSProblem.evaluate(BatchLSEstimator.java:615)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.GaussNewtonOptimizer.optimize(GaussNewtonOptimizer.java:163)
	at org.orekit.estimation.leastsquares.BatchLSEstimator.estimate(BatchLSEstimator.java:435)

and when I add 1st batch measurements to IOD acquired from 2nd batch, I got this error:

JavaError                                 Traceback (most recent call last)
Input In [16], in <cell line: 1>()
----> 1 estimatedPropagatorArray = estimator.estimate()

JavaError: <super: <class 'JavaError'>, <JavaError object>>
    Java stacktrace:
org.orekit.errors.OrekitException: minimal step size (1,00E-03) reached, integration needs 8,91E-04
	at org.orekit.errors.OrekitException.unwrap(OrekitException.java:154)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator.integrateDynamics(AbstractIntegratedPropagator.java:511)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator.propagate(AbstractIntegratedPropagator.java:425)
	at org.orekit.propagation.PropagatorsParallelizer.propagate(PropagatorsParallelizer.java:140)
	at org.orekit.estimation.leastsquares.AbstractBatchLSModel.value(AbstractBatchLSModel.java:322)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.LeastSquaresFactory$LocalLeastSquaresProblem.evaluate(LeastSquaresFactory.java:440)
	at org.orekit.estimation.leastsquares.BatchLSEstimator$TappedLSProblem.evaluate(BatchLSEstimator.java:615)
	at org.hipparchus.optim.nonlinear.vector.leastsquares.GaussNewtonOptimizer.optimize(GaussNewtonOptimizer.java:163)
	at org.orekit.estimation.leastsquares.BatchLSEstimator.estimate(BatchLSEstimator.java:435)
Caused by: org.hipparchus.exception.MathIllegalArgumentException: minimal step size (1,00E-03) reached, integration needs 8,91E-04
	at org.hipparchus.ode.nonstiff.StepsizeHelper.filterStep(StepsizeHelper.java:179)
	at org.hipparchus.ode.nonstiff.EmbeddedRungeKuttaIntegrator.integrate(EmbeddedRungeKuttaIntegrator.java:276)
	at org.orekit.propagation.integration.AbstractIntegratedPropagator.integrateDynamics(AbstractIntegratedPropagator.java:477)
	... 7 more

So, right now I’m thinking data my data is not precise enough, maybe there were bad weather that day, or something. Second batch looks much better, but clearly there is something wrong with it as well.

Hi again @jlipinski,

That may be the problem indeed.

First issue states that your satellite crashed (or almost) on the Earth. Second one could be fixed with a lower minimal step but it tends to indicate there is a problem with either the measurements or the model.
Try to de-activate SRP and drag first for this OD on both days and see what you end up with.

Since your satellite is navigating between approximately 640km and 870km of altitude, the atmospheric drag should not have a big effect on a one day propagation.
This is actually quite an elliptical orbit you’re dealing with (compared to classical LEO circular orbits that have an eccentricity 10 to 15 times smaller than yours).

Beware that TLE with SGP4 is a mean model so comparing a point to an osculating orbit can be misleading.
See this post from @luc for more on that.

How did you convert camera measurements to PV in ITRF ?
Wouldn’t it be better to directly use the measurements from the camera (like RADEC or AZEL ?).

Orekit has AngularRaDec and AngularAzel measurements available.

Something you could try to evaluate the quality of OD is getting and plotting the residuals.
There are pointers on how to do it in this recent post.
This one happens to be on OD with RADEC measurements so you may find some ideas about this too.

I don’t think they are, you managed to perform an OD on both batches and make it converge to an orbit close enough to what you expected. If your observations were completely wrong, that would never have happened.
That being said, your observations may be of poor quality and that’s why you cannot follow your object properly on a daily basis.
Beware that angular measurements will badly model the shape of the orbit (a, e and ω) on such short arcs.

Hi, @MaximeJ and @jlipinski,

I tried OD using your data.

Firstly, I think we can compare the position and velocity calculate by TLE to your measurement.
The position and velocity is calculate using TLEPropagator.

All are transformed to the same frame eme2000.

The related TLE is as followings, with epoch ‘2022-06-26T21:16:49.3464Z’.

1  7490U 74083A   22177.88668225  .00000113  00000-0  57075-4 0  9999
2  7490  81.1881 120.1060 0029938 222.0960 137.7911 14.10101506450570

And I see that, the difference in position is about 1000m, it’s OK I think. But the difference in velocity is about 100m/s, it’s quite large.
So I think the data quality is very poor. And it’s too short.

Even though, the OD can be done, but the residual is large, about 1000km in position and 100m/s in velocity.

Is there something wrong in your measurement?

Unfortunately I have detected flaws in my cameras used for observations causing data to be inaccurate enough to yield wrong results. Thank you all for help, I hope I won’t need to come back here after I fix my hardware.

Hi @jlipinski,

Too bad for your camera… and you’re welcome for the help !

Don’t hesitate to come back on the forum to share your results (or even images!) or just tell us that it worked :wink:
It’s always a pleasure to have a feedback.