Module: sunlineUKF
Executive Summary
This module implements and tests a Unscented 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 |
name of the navigation output message containing the estimated states |
|
filtDataOutMsg |
name of the output filter data message |
|
cssDataInMsg |
name of the CSS sensor input message |
|
cssConfigInMsg |
name of the CSS configuration input message |
Functions
-
void SelfInit_sunlineUKF(SunlineUKFConfig *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
- Parameters:
configData – The configuration data associated with the CSS WLS estimator
moduleID – The module identifier
- Returns:
void
-
void Update_sunlineUKF(SunlineUKFConfig *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
- Parameters:
configData – The configuration data associated with the CSS estimator
callTime – The clock time at which the function was called (nanoseconds)
moduleID – The module identifier
- Returns:
void
-
void Reset_sunlineUKF(SunlineUKFConfig *configData, uint64_t callTime, int64_t moduleID)
This method resets the sunline attitude filter to an initial state and initializes the internal estimation matrices.
- Parameters:
configData – The configuration data associated with the CSS estimator
callTime – The clock time at which the function was called (nanoseconds)
moduleID – The module identifier
- Returns:
void
-
void sunlineUKFTimeUpdate(SunlineUKFConfig *configData, double updateTime)
This method performs the time update for the sunline kalman filter. It propagates the sigma points forward in time and then gets the current covariance and state estimates.
- Parameters:
configData – The configuration data associated with the CSS estimator
updateTime – The time that we need to fix the filter to (seconds)
- Returns:
void
-
void sunlineUKFMeasUpdate(SunlineUKFConfig *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.
- Parameters:
configData – The configuration data associated with the CSS estimator
updateTime – The time that we need to fix the filter to (seconds)
- Returns:
void
-
void sunlineStateProp(double *stateInOut, double dt)
This method propagates a sunline state vector forward in time. Note that the calling parameter is updated in place to save on data copies.
- Parameters:
stateInOut – The state that is propagated
dt – Time step (s)
- Returns:
void
-
void sunlineUKFMeasModel(SunlineUKFConfig *configData)
This method computes what the expected measurement vector is for each CSS that is present on the spacecraft. All data is transacted from the main data structure for the model because there are many variables that would have to be updated otherwise.
- Parameters:
configData – The configuration data associated with the CSS estimator
- Returns:
void
-
struct SunlineUKFConfig
- #include <sunlineUKF.h>
Top level structure for the CSS-based unscented Kalman Filter. Used to estimate the sun state in the vehicle body frame.
Public Members
The name of the output message
-
SunlineFilterMsg_C filtDataOutMsg
The name of the output filter data message
-
CSSArraySensorMsg_C cssDataInMsg
The name of the Input message
-
CSSConfigMsg_C cssConfigInMsg
[-] The name of the CSS configuration message
-
int numStates
[-] Number of states for this filter
-
int countHalfSPs
[-] Number of sigma points over 2
-
int 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 wM[2 * SKF_N_STATES + 1]
[-] Weighting vector for sigma points
-
double wC[2 * SKF_N_STATES + 1]
[-] Weighting vector for sigma points
-
double state[SKF_N_STATES]
[-] State estimate for time TimeTag
-
double sBar[SKF_N_STATES * SKF_N_STATES]
[-] Time updated covariance
-
double covar[SKF_N_STATES * SKF_N_STATES]
[-] covariance
-
double xBar[SKF_N_STATES]
[-] Current mean state estimate
-
double obs[MAX_N_CSS_MEAS]
[-] Observation vector for frame
-
double yMeas[MAX_N_CSS_MEAS * (2 * SKF_N_STATES + 1)]
[-] Measurement model data
-
double postFits[MAX_N_CSS_MEAS]
[-] PostFit residuals
-
double SP[(2 * SKF_N_STATES + 1) * SKF_N_STATES]
[-] sigma point matrix
-
double qNoise[SKF_N_STATES * SKF_N_STATES]
[-] process noise matrix
-
double sQnoise[SKF_N_STATES * SKF_N_STATES]
[-] 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
-
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
-
BSKLogger *bskLogger
BSK Logging.