Skip to main content
Attitude determination modules process raw sensor data to produce the best available estimate of spacecraft orientation. They sit between hardware sensor modules and attitude guidance or control modules in the FSW pipeline.

CSS-based estimation

Least-squares and Kalman filter approaches that use coarse sun sensor arrays.

Star-tracker UKF

Unscented Kalman filter fusing star-tracker and reaction-wheel data for inertial attitude.

Sunline filters

EKF, SuKF and UKF variants that track the body-relative sun direction vector.

Ephemeris sunline

Computes the sun heading from spacecraft and sun position ephemerides, no sensor required.

CSS weighted least-squares estimator (cssWlsEst)

This module uses a weighted least-squares minimum-norm algorithm to estimate the body-relative sun heading from a cluster of coarse sun sensors (CSS). By differencing two successive sun-heading solutions it also derives the inertial angular velocity vector. Because rotations about the sun-heading axis are unobservable, the returned angular velocity contains only the rate components orthogonal to that heading.

Messages

VariableTypeDirectionDescription
cssDataInMsgCSSArraySensorMsgPayloadInputCSS sensor readings
cssConfigInMsgCSSConfigMsgPayloadInputCSS geometry configuration
navStateOutMsgNavAttMsgPayloadOutputEstimated sun heading and angular velocity
cssWLSFiltResOutMsgSunlineFilterMsgPayloadOutputFilter residuals and state data
from Basilisk.fswAlgorithms import cssWlsEst

cssEst = cssWlsEst.cssWlsEst()
cssEst.ModelTag = "cssWlsEst"

# connect sensor and configuration messages
cssEst.cssDataInMsg.subscribeTo(cssArrayMsg)
cssEst.cssConfigInMsg.subscribeTo(cssConfigMsg)

scSim.AddModelToTask(taskName, cssEst)

Sunline EKF (sunlineEKF)

An Extended Kalman Filter that estimates the body-relative sunline direction from CSS measurements. The EKF state is the unit sun-direction vector together with a rate bias, and CSS cosine readings form the measurement model.

Messages

VariableTypeDirectionDescription
cssDataInMsgCSSArraySensorMsgPayloadInputCSS sensor readings
cssConfigInMsgCSSConfigMsgPayloadInputCSS geometry configuration
navStateOutMsgNavAttMsgPayloadOutputEstimated sun heading
filtDataOutMsgSunlineFilterMsgPayloadOutputFilter state and covariance data

Sunline switch-UKF (sunlineSuKF)

A Switch Unscented Kalman Filter for sunline estimation. The switching logic avoids the MRP singularity at 360° and is based on the Square-Root UKF formulation. It accepts the same CSS input messages as sunlineEKF and produces the same NavAttMsgPayload and SunlineFilterMsgPayload outputs.
Use sunlineSuKF instead of sunlineEKF when CSS noise is non-Gaussian or when you need numerically robust square-root covariance propagation.

Sunline UKF (sunlineUKF)

A standard Unscented Kalman Filter variant for sunline estimation. It shares the same I/O interface as sunlineSuKF but propagates the full covariance matrix rather than its square root.

Heading switch-UKF (headingSuKF)

A generalized version of the sunline SuKF that estimates an arbitrary heading direction rather than specifically the sunline. This makes it suitable for optical navigation scenarios where a camera tracks a body-fixed feature direction.

Messages

VariableTypeDirectionDescription
opnavDataInMsgOpNavMsgPayloadInputOptical navigation measurement
cameraConfigInMsgCameraConfigMsgPayloadInput(optional) Camera intrinsics
opnavDataOutMsgOpNavMsgPayloadOutputFiltered heading measurement
filtDataOutMsgHeadingFilterMsgPayloadOutputFilter state and covariance

Inertial UKF (inertialUKF)

Filters star-tracker measurements together with reaction-wheel data to produce the best available inertial attitude estimate. The UKF uses Modified Rodrigues Parameters (MRPs) as the attitude representation to avoid singularities. Multiple camera heads can provide simultaneous star-tracker inputs.

Messages

VariableTypeDirectionDescription
gyrBuffInMsgAccDataMsgPayloadInputRate gyro buffer
rwSpeedsInMsgRWSpeedMsgPayloadInputReaction-wheel speeds
rwParamsInMsgRWArrayConfigMsgPayloadInputRW configuration (can be empty)
massPropsInMsgVehicleConfigMsgPayloadInputSpacecraft inertia
navStateOutMsgNavAttMsgPayloadOutputEstimated inertial attitude and rate
filtDataOutMsgInertialFilterMsgPayloadOutputFilter state, covariance
from Basilisk.fswAlgorithms import inertialUKF

attUKF = inertialUKF.InertialUKF()
attUKF.ModelTag = "inertialUKF"

# connect required messages
attUKF.gyrBuffInMsg.subscribeTo(gyroMsg)
attUKF.rwSpeedsInMsg.subscribeTo(rwSpeedMsg)
attUKF.rwParamsInMsg.subscribeTo(rwParamsMsg)
attUKF.massPropsInMsg.subscribeTo(vehConfigMsg)

scSim.AddModelToTask(taskName, attUKF)

Ephemeris sunline (sunlineEphem)

Computes the sun-heading vector directly from spacecraft and sun ephemeris messages without requiring any sensor input. This is useful for simulation scenarios or as a fallback when CSS data is unavailable.

Messages

VariableTypeDirectionDescription
sunPositionInMsgEphemerisMsgPayloadInputSun ephemeris
scPositionInMsgNavTransMsgPayloadInputSpacecraft translational state
scAttitudeInMsgNavAttMsgPayloadInputSpacecraft attitude
navStateOutMsgNavAttMsgPayloadOutputBody-relative sun heading

O’Keefe EKF (okeefeEKF)

A CSS-based EKF that applies the O’Keefe measurement model for improved accuracy when the spacecraft attitude is partially known. Shares the standard CSS input interface (CSSArraySensorMsgPayload, CSSConfigMsgPayload) and outputs NavAttMsgPayload and SunlineFilterMsgPayload.

Build docs developers (and LLMs) love