Module: 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.

Module I/O Messages

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


Functions

void SelfInit_sunlineSuKF(SunlineSuKFConfig *configData, int64_t moduleID)

This method initializes the configData for theCSS WLS estimator.

Parameters:
  • configData – The configuration data associated with the CSS WLS estimator

  • moduleID – The module identifier

Returns:

void

void Update_sunlineSuKF(SunlineSuKFConfig *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_sunlineSuKF(SunlineSuKFConfig *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

int sunlineSuKFTimeUpdate(SunlineSuKFConfig *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

int sunlineSuKFMeasUpdate(SunlineSuKFConfig *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 *b_vec, 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

  • b_Vec – b vector

  • dt – time step (s)

Returns:

void

void sunlineSuKFMeasModel(SunlineSuKFConfig *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

void sunlineSuKFComputeDCM_BS(double sunheading[SKF_N_STATES_HALF], double bVec[SKF_N_STATES_HALF], double *dcm)
void sunlineSuKFSwitch(double *bVec_B, double *states, double *covar)

This method computes the dcms necessary for the switch between the two frames. It the switches the states and the covariance, and sets s2 to be the new, different vector of the body frame.

Parameters:
  • bVec_B – Pointer to b vector

  • states – Pointer to the states

  • covar – Pointer to the covariance

Returns:

void

void sunlineSuKFCleanUpdate(SunlineSuKFConfig *configData)

This method cleans the filter states after a bad upadate on the fly. It removes the potentially corrupted previous estimates and puts the filter back to a working state.

Parameters:

configData – The configuration data associated with the CSS estimator

Returns:

void

struct SunlineSuKFCFit
#include <sunlineSuKF.h>

structure containing the fitting parameters

Public Members

double cssRelScale

Relative scale factor for this CSS.

double cssKellPow

CSS kelly estimate power.

double cssKellFact

CSS kelly scale factor.

struct SunlineSuKFConfig
#include <sunlineSuKF.h>

Data structure for CSS Switch unscented kalman filter estimator.

Public Members

NavAttMsg_C navStateOutMsg

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

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

&#8212; Number of currently active CSS sensors

uint32_t numCSSTotal

[-] Count on the number of CSS we have on the spacecraft

double sensorUseThresh

&#8212; Threshold below which we discount sensors

NavAttMsgPayload outputSunline

&#8212; 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.