okeefeEKF#
Executive Summary#
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
Message Connection Descriptions#
The following table lists all the module input and output messages. The module msg connection is set by the user from python. The msg type contains a link to the message structure definition, while the description provides information on what this message is used for.
Msg Variable Name |
Msg Type |
Description |
---|---|---|
navStateOutMsg |
NavAttMsgPayload |
name of the navigation output message containing the estimated states |
filtDataOutMsg |
SunlineFilterMsgPayload |
name of the output filter data message |
cssDataInMsg |
CSSArraySensorMsgPayload |
name of the CSS sensor input message |
cssConfigInMsg |
CSSConfigMsgPayload |
name of the CSS configuration input message |
Class OkeefeEKF#
-
class OkeefeEKF : public SysModel#
Data structure for CSS Extended kalman filter estimator without gyros measurements.
Public Functions
-
void reset(uint64_t callTime) override#
This method resets the sunline attitude filter to an initial state and initializes the internal estimation matrices.
- Parameters:
callTime – The clock time at which the function was called (nanoseconds)
- Returns:
void
-
void updateState(uint64_t callTime) override#
This method takes the parsed CSS sensor data and outputs an estimate of the sun vector in the ADCS body frame
- Parameters:
callTime – The clock time at which the function was called (nanoseconds)
- Returns:
void
-
void sunlineTimeUpdate(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.
- Parameters:
updateTime – The time that we need to fix the filter to (seconds)
- Returns:
void
-
void sunlineMeasUpdate(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.
- Parameters:
updateTime – The time that we need to fix the filter to (seconds)
- Returns:
void
Public Members
The name of the output message
-
Message<SunlineFilterMsgPayload> filtDataOutMsg#
The name of the output filter data message
-
ReadFunctor<CSSArraySensorMsgPayload> cssDataInMsg#
The name of the Input message
-
ReadFunctor<CSSConfigMsgPayload> cssConfigInMsg#
[-] 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 statecovar/etc
-
double state[SKF_N_STATES_HALF]#
[-] State estimate for time TimeTag
-
double prev_states[SKF_N_STATES_HALF]#
[-] State estimate for previous time TimeTag
-
double omega[SKF_N_STATES_HALF]#
[-] Rotation rate vector
-
double x[SKF_N_STATES_HALF]#
[-] State errors
-
double xBar[SKF_N_STATES_HALF]#
[-] Current time updated mean state estimate
-
double covarBar[SKF_N_STATES_HALF * SKF_N_STATES_HALF]#
[-] Time updated covariance
-
double covar[SKF_N_STATES_HALF * SKF_N_STATES_HALF]#
[-] covariance
-
double stateTransition[SKF_N_STATES_HALF * SKF_N_STATES_HALF]#
[-] covariance
-
double kalmanGain[SKF_N_STATES_HALF * MAX_N_CSS_MEAS]#
Kalman Gain
-
double dynMat[SKF_N_STATES_HALF * SKF_N_STATES_HALF]#
[-] Dynamics Matrix, A
-
double measMat[MAX_N_CSS_MEAS * SKF_N_STATES_HALF]#
[-] 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_HALF * SKF_N_STATES_HALF]#
[-] 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
-
uint32_t numStates#
[-] Number of states for this filter
-
size_t numObs#
[-] Number of measurements this cycle
-
uint32_t numActiveCss#
— Number of currently active CSS sensors
-
uint32_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
-
NavAttMsgPayload outputSunline#
— Output sunline estimate data
-
CSSArraySensorMsgPayload cssSensorInBuffer#
[-] CSS sensor data read in from message bus
-
BSKLogger bskLogger = {}#
BSK Logging.
-
void reset(uint64_t callTime) override#