sunlineSEKF#
Executive Summary#
This module implements and tests a Switch Extended Kalman Filter in order to estimate the sunline direction.
More information 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 SunlineSEKF#
-
class SunlineSEKF : public SysModel#
Top level structure for the CSS-based Switch Extended Kalman Filter. Used to estimate the sun state in the vehicle body frame.
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
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 bVec_B[SKF_N_STATES_HALF]#
[-] current vector of the b frame used to make Switch frame
-
double switchTresh#
[-] Cosine of angle between singularity and S-frame. If close to 1, the threshold for switching frames is lower. If closer to 0.5 singularity is more largely avoided but switching is more frequent
-
double state[EKF_N_STATES_SWITCH]#
[-] State estimate for time TimeTag
-
double x[EKF_N_STATES_SWITCH]#
State errors
-
double xBar[EKF_N_STATES_SWITCH]#
[-] Current mean state estimate
-
double covarBar[EKF_N_STATES_SWITCH * EKF_N_STATES_SWITCH]#
[-] Time updated covariance
-
double covar[EKF_N_STATES_SWITCH * EKF_N_STATES_SWITCH]#
[-] covariance
-
double stateTransition[EKF_N_STATES_SWITCH * EKF_N_STATES_SWITCH]#
[-] State transition Matrix
-
double kalmanGain[EKF_N_STATES_SWITCH * MAX_N_CSS_MEAS]#
Kalman Gain
-
double dynMat[EKF_N_STATES_SWITCH * EKF_N_STATES_SWITCH]#
[-] Dynamics Matrix, A
-
double measMat[MAX_N_CSS_MEAS * EKF_N_STATES_SWITCH]#
[-] Measurement Matrix, H
-
double W_BS[EKF_N_STATES_SWITCH * EKF_N_STATES_SWITCH]#
[-] Switch Matrix to bring states and covariance to new S-frame when switch occurs
-
double obs[MAX_N_CSS_MEAS]#
[-] Observation vector for frame
-
double yMeas[MAX_N_CSS_MEAS]#
[-] Linearized measurement model data
-
double postFits[MAX_N_CSS_MEAS]#
[-] PostFit residuals
-
double procNoise[(EKF_N_STATES_SWITCH - 3) * (EKF_N_STATES_SWITCH - 3)]#
[-] process noise matrix
-
double measNoise[MAX_N_CSS_MEAS * MAX_N_CSS_MEAS]#
[-] Maximally sized obs noise matrix
-
double cssNHat_B[MAX_NUM_CSS_SENSORS * 3]#
[-] CSS normal vectors converted over to body
-
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#