Module: sunlineUKF

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


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

Return

void

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

void CrossInit_sunlineUKF(SunlineUKFConfig *configData, int64_t moduleID)

This method performs the second stage of initialization for the CSS sensor interface. It’s primary function is to link the input messages that were created elsewhere.

Return

void

Parameters
  • configData: The configuration data associated with the CSS interface

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

Return

void

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

  • callTime: The clock time at which the function was called (nanoseconds)

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.

Return

void

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

  • callTime: The clock time at which the function was called (nanoseconds)

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.

Return

void

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

  • updateTime: The time that we need to fix the filter to (seconds)

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.

Return

void

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

  • updateTime: The time that we need to fix the filter to (seconds)

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.

Return

void

Parameters
  • stateInOut: The state that is propagated

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.

Return

void

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

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

char navStateOutMsgName[MAX_STAT_MSG_LENGTH]

The name of the output message

char filtDataOutMsgName[MAX_STAT_MSG_LENGTH]

The name of the output filter data message

char cssDataInMsgName[MAX_STAT_MSG_LENGTH]

The name of the Input message

char cssConfigInMsgName[MAX_STAT_MSG_LENGTH]

[-] 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]
double obs[MAX_N_CSS_MEAS]

[-] Current mean state estimate [-] 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

NavAttIntMsg outputSunline

Output sunline estimate data

CSSArraySensorIntMsg cssSensorInBuffer

[-] CSS sensor data read in from message bus

int32_t navStateOutMsgId

ID for the outgoing body estimate message

int32_t filtDataOutMsgId

[-] ID for the filter data output message

int32_t cssDataInMsgId

ID for the incoming CSS sensor message

int32_t cssConfigInMsgId

[-] ID associated with the CSS configuration data

BSKLogger *bskLogger

BSK Logging.