sunlineSuKF#
Executive Summary#
This module implements and tests a Switch Unscented Kalman Filter in order to estimate the sunline direction. The theory used in this module can be found in this paper.
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 SunlineSuKF#
-
class SunlineSuKF : public SysModel#
Data structure for CSS Switch unscented kalman filter estimator.
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
-
size_t numStates#
[-] Number of states for this filter
-
size_t countHalfSPs#
[-] Number of sigma points over 2
-
size_t numObs#
[-] Number of measurements this cycle
-
double beta#
[-] Beta parameter for filter
-
double alpha#
[-] Alpha parameter for filter
-
double kappa#
[-] Kappa parameter for filter
-
double lambdaVal#
[-] Lambda parameter for filter
-
double gamma#
[-] Gamma parameter for filter
-
double qObsVal#
[-] CSS instrument 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 frame
-
double switchTresh#
[-] Threshold for switching frames
-
double stateInit[SKF_N_STATES_SWITCH]#
[-] State to initialize filter to
-
double state[SKF_N_STATES_SWITCH]#
[-] State estimate for time TimeTag
-
double statePrev[SKF_N_STATES_SWITCH]#
[-] Previous state logged for clean
-
double wM[2 * SKF_N_STATES_SWITCH + 1]#
[-] Weighting vector for sigma points
-
double wC[2 * SKF_N_STATES_SWITCH + 1]#
[-] Weighting vector for sigma points
-
double sBar[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] Time updated covariance
-
double sBarPrev[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] Time updated covariance logged for clean
-
double covarInit[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] covariance to init to
-
double covar[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] covariance
-
double covarPrev[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] Covariance logged for clean
-
double xBar[SKF_N_STATES_SWITCH]#
[-] Current mean state estimate
-
double obs[MAX_N_CSS_MEAS]#
[-] Observation vector for frame
-
double yMeas[MAX_N_CSS_MEAS * (2 * SKF_N_STATES_SWITCH + 1)]#
[-] Measurement model data
-
double postFits[MAX_N_CSS_MEAS]#
[-] PostFit residuals
-
double SP[(2 * SKF_N_STATES_SWITCH + 1) * SKF_N_STATES_SWITCH]#
[-] sigma point matrix
-
double qNoise[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] process noise matrix
-
double sQnoise[SKF_N_STATES_SWITCH * SKF_N_STATES_SWITCH]#
[-] cholesky of Qnoise
-
double qObs[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
-
double CBias[MAX_NUM_CSS_SENSORS]#
[-] CSS individual calibration coefficients
-
SunlineSuKFCFit kellFits[MAX_NUM_CSS_SENSORS]#
[-] Curve fit components for CSS sensors
-
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
-
NavAttMsgPayload outputSunline#
— Output sunline estimate data
-
CSSArraySensorMsgPayload cssSensorInBuffer#
[-] CSS sensor data read in from message bus
-
uint32_t filterInitialized#
[-] Flag indicating if filter has been init or not
-
BSKLogger bskLogger = {}#
BSK Logging.
-
void reset(uint64_t callTime) override#