Module: sunlineEKF¶
This module implements and tests a Extended Kalman Filter in order to estimate the sunline direction.
More information on can be found in the
PDF Description
Functions
-
void
SelfInit_sunlineEKF
(sunlineEKFConfig *configData, int64_t moduleID)¶ This method initializes the configData for theCSS WLS estimator. It checks to ensure that the inputs are sane and then creates the output message
- Return
void
- Parameters
configData
: The configuration data associated with the CSS WLS estimatormoduleID
: The module identifier
-
void
CrossInit_sunlineEKF
(sunlineEKFConfig *configData, int64_t moduleID)¶ This method performs the second stage of initialization for the CSS sensor interface. It’s primary function is to link the input messages that were created elsewhere.
- Return
void
- Parameters
configData
: The configuration data associated with the CSS interfacemoduleID
: The module identifier
-
void
Reset_sunlineEKF
(sunlineEKFConfig *configData, uint64_t callTime, int64_t moduleID)¶ This method resets the sunline attitude filter to an initial state and initializes the internal estimation matrices.
- Return
void
- Parameters
configData
: The configuration data associated with the CSS estimatorcallTime
: The clock time at which the function was called (nanoseconds)moduleID
: The module identifier
-
void
Update_sunlineEKF
(sunlineEKFConfig *configData, uint64_t callTime, int64_t moduleID)¶ This method takes the parsed CSS sensor data and outputs an estimate of the sun vector in the ADCS body frame
- Return
void
- Parameters
configData
: The configuration data associated with the CSS estimatorcallTime
: The clock time at which the function was called (nanoseconds)moduleID
: The module identifier
-
void
sunlineTimeUpdate
(sunlineEKFConfig *configData, double updateTime)¶ This method performs the time update for the sunline kalman filter. It calls for the updated Dynamics Matrix, as well as the new states and STM. It then updates the covariance, with process noise.
- Return
void
- Parameters
configData
: The configuration data associated with the CSS estimatorupdateTime
: The time that we need to fix the filter to (seconds)
-
void
sunlineMeasUpdate
(sunlineEKFConfig *configData, double updateTime)¶ This method performs the measurement update for the sunline kalman filter. It applies the observations in the obs vectors to the current state estimate and updates the state/covariance with that information.
- Return
void
- Parameters
configData
: The configuration data associated with the CSS estimatorupdateTime
: The time that we need to fix the filter to (seconds)
-
void
sunlineStateSTMProp
(double dynMat[SKF_N_STATES * SKF_N_STATES], double dt, double *stateInOut, double *stateTransition)¶ This method propagates a sunline state vector forward in time. Note that the calling parameter is updated in place to save on data copies. This also updates the STM using the dynamics matrix.
- Return
void
- Parameters
dynMat
:dt
:stateInOut
:stateTransition
:
-
void
sunlineHMatrixYMeas
(double states[SKF_N_STATES], int numCSS, double cssSensorCos[MAX_N_CSS_MEAS], double sensorUseThresh, double cssNHat_B[MAX_NUM_CSS_SENSORS * 3], double CBias[MAX_NUM_CSS_SENSORS], double *obs, double *yMeas, int *numObs, double *measMat)¶ This method computes the H matrix, defined by dGdX. As well as computing the innovation, difference between the measurements and the expected measurements. This methods modifies the numObs, measMat, and yMeas.
- Return
void
- Parameters
states
:numCSS
: The total number of CSScssSensorCos
: The list of the measurements from the CSSssensorUseThresh
: Thresh The Threshold below which the measuremnts are not readcssNHat_B
: The normals vector for each of the CSSsCBias
: Array of sensor biasesobs
: Pointer to the observationsyMeas
: Pointer to the innovationnumObs
: Pointer to the number of observationsmeasMat
: Point to the H measurement matrix
-
void
sunlineKalmanGain
(double covarBar[SKF_N_STATES * SKF_N_STATES], double hObs[MAX_N_CSS_MEAS * SKF_N_STATES], double qObsVal, int numObs, double *kalmanGain)¶ This method computes the Kalman gain given the measurements.
- Return
void
- Parameters
covarBar
: The time updated covariancehObs
: The H matrix filled with the observationsqObsVal
: The observation noisenumObs
: The number of observationskalmanGain
: Pointer to the Kalman Gain
-
void
sunlineDynMatrix
(double stateInOut[SKF_N_STATES], double dt, double *dynMat)¶ This method computes the dynamics matrix, which is the derivative of the dynamics F by the state X, evaluated at the reference state. It takes in the configure data and updates this A matrix pointer called dynMat
- Return
void
- Parameters
states
: Updated statesdt
: Time stepdynMat
: Pointer to the Dynamic Matrix
-
void
sunlineCKFUpdate
(double xBar[SKF_N_STATES], double kalmanGain[SKF_N_STATES * MAX_N_CSS_MEAS], double covarBar[SKF_N_STATES * SKF_N_STATES], double qObsVal, int numObs, double yObs[MAX_N_CSS_MEAS], double hObs[MAX_N_CSS_MEAS * SKF_N_STATES], double *x, double *covar)¶ This method computes the updated with a Classical Kalman Filter
- Return
void
- Parameters
xBar
: The state after a time updatekalmanGain
: The computed Kalman GaincovarBar
: The time updated covarianceqObsVal
: The observation noisenumObs
: The amount of CSSs that get measurementsyObs
: The y vector after receiving the measurementshObs
: The H matrix filled with the observationsx
: Pointer to the state error for modificationcovar
: Pointer to the covariance after update
-
void
sunlineEKFUpdate
(double kalmanGain[SKF_N_STATES * MAX_N_CSS_MEAS], double covarBar[SKF_N_STATES * SKF_N_STATES], double qObsVal, int numObs, double yObs[MAX_N_CSS_MEAS], double hObs[MAX_N_CSS_MEAS * SKF_N_STATES], double *states, double *x, double *covar)¶ This method computes the updated with a Extended Kalman Filter
- Return
void
- Parameters
kalmanGain
: The computed Kalman GaincovarBar
: The time updated covarianceqObsVal
: The observation noisenumObs
: The amount of CSSs that get measurementsyObs
: The y vector after receiving the measurementshObs
: The H matrix filled with the observationsstates
: Pointer to the statesx
: Pointer to the state error for modificationcovar
: Pointer to the covariance after update
-
struct
sunlineEKFConfig
¶ - #include <sunlineEKF.h>
Top level structure for the CSS-based Extended Kalman Filter. Used to estimate the sun state in the vehicle body frame.
Public Members
The name of the output message
-
char
filtDataOutMsgName
[MAX_STAT_MSG_LENGTH
]¶ The name of the output filter data message
-
char
cssDataInMsgName
[MAX_STAT_MSG_LENGTH
]¶ The name of the Input message
-
char
cssConfigInMsgName
[MAX_STAT_MSG_LENGTH
]¶ [-] The name of the CSS configuration message
-
double
qObsVal
¶ [-] CSS instrument noise parameter
-
double
qProcVal
¶ [-] Process noise parameter
-
double
dt
¶ [s] seconds since last data epoch
-
double
timeTag
¶ [s] Time tag for state/covar
-
double
state
[SKF_N_STATES
]¶ [-] State estimate for time TimeTag
-
double
x
[SKF_N_STATES
]¶ State errors
-
double
xBar
[SKF_N_STATES
]¶ [-] Current mean time updated state estimate
-
double
covarBar
[SKF_N_STATES
*SKF_N_STATES
]¶ [-] Time updated covariance
-
double
covar
[SKF_N_STATES
*SKF_N_STATES
]¶ [-] covariance
-
double
stateTransition
[SKF_N_STATES
*SKF_N_STATES
]¶ [-] State Transtion Matrix
-
double
kalmanGain
[SKF_N_STATES
*MAX_N_CSS_MEAS
]¶ Kalman Gain
-
double
dynMat
[SKF_N_STATES
*SKF_N_STATES
]¶ [-] Dynamics Matrix, A
-
double
measMat
[MAX_N_CSS_MEAS
*SKF_N_STATES
]¶ [-] Measurement Matrix H
-
double
obs
[MAX_N_CSS_MEAS
]¶ [-] Observation vector for frame
-
double
yMeas
[MAX_N_CSS_MEAS
]¶ [-] Linearized measurement model data
-
double
procNoise
[SKF_N_STATES
/ 2 *SKF_N_STATES
/ 2]¶ [-] process noise matrix
-
double
measNoise
[MAX_N_CSS_MEAS
*MAX_N_CSS_MEAS
]¶ [-] Maximally sized obs noise matrix
-
double
postFits
[MAX_N_CSS_MEAS
]¶ [-] PostFit residuals
-
double
cssNHat_B
[MAX_NUM_CSS_SENSORS
* 3]¶ [-] CSS normal vectors converted over to body
-
double
CBias
[MAX_NUM_CSS_SENSORS
]¶ [-] CSS individual calibration coefficients
-
size_t
numStates
¶ [-] Number of states for this filter
-
int
numObs
¶ [-] Number of measurements this cycle
-
size_t
numActiveCss
¶ Number of currently active CSS sensors
-
size_t
numCSSTotal
¶ [-] Count on the number of CSS we have on the spacecraft
-
double
sensorUseThresh
¶ Threshold below which we discount sensors
-
double
eKFSwitch
¶ Max covariance element after which the filter switches to an EKF update
-
NavAttIntMsg
outputSunline
¶ Output sunline estimate data
-
CSSArraySensorIntMsg
cssSensorInBuffer
¶ [-] CSS sensor data read in from message bus
ID for the outgoing body estimate message
-
int32_t
filtDataOutMsgId
¶ [-] ID for the filter data output message
-
int32_t
cssDataInMsgId
¶ ID for the incoming CSS sensor message
-
int32_t
cssConfigInMsgId
¶ [-] ID associated with the CSS configuration data
-
BSKLogger *
bskLogger
¶ BSK Logging.