Skip to main content
Optical navigation (OpNav) modules estimate spacecraft position from images of planetary bodies. Raw images are first processed by image-analysis modules (e.g., houghCircles, pixelLineConverter) to extract geometric measurements, which are then filtered by the modules on this page.

Relative OD UKF

Filters planet-image position measurements to estimate spacecraft position in the inertial frame.

Pixel-line bias UKF

Extends the relative OD UKF with pixel and line measurement bias estimation.

Fault detection

Merges or selects between two OpNav measurement sources with configurable fault tolerance.

Heading SuKF

Estimates an arbitrary heading direction from OpNav measurements (see Attitude Determination).

Relative OD UKF (relativeODuKF)

This module filters position measurements derived from planetary images to estimate the spacecraft’s relative position with respect to the observed body, expressed in the inertial frame. It uses an Unscented Kalman Filter (UKF). The raw image measurements are first processed by houghCircles and pixelLineConverter to produce the OpNavMsgPayload inputs this filter consumes.

Messages

VariableTypeDirectionDescription
opNavInMsgOpNavMsgPayloadInputProcessed position measurement from image pipeline
navStateOutMsgNavTransMsgPayloadOutputEstimated spacecraft position and velocity
filtDataOutMsgOpNavFilterMsgPayloadOutputFilter state, covariance, and residuals
from Basilisk.fswAlgorithms import relativeODuKF
import numpy as np

odFilter = relativeODuKF.RelativeODuKF()
odFilter.ModelTag = "relativeODuKF"

# initial state: position [m] and velocity [m/s] in inertial frame
odFilter.stateInit = [7000.0e3, 0.0, 0.0, 0.0, 7.5e3, 0.0]

# process and measurement noise
odFilter.processNoise = np.diag([1.0, 1.0, 1.0, 0.001, 0.001, 0.001]).tolist()
odFilter.measNoiseScaling = 1.0

odFilter.opNavInMsg.subscribeTo(pixelLineConverterMsg)
scSim.AddModelToTask(taskName, odFilter)

Pixel-line bias UKF (pixelLineBiasUKF)

Extends the relative OD UKF by incorporating pixel and line measurement biases directly into the filter state. Instead of relying on pre-converted position measurements, it reads detected circle data (OpNavCirclesMsgPayload) and integrates the pixel-to-line transformation into the measurement model. This makes it more robust to systematic camera calibration errors.

Messages

VariableTypeDirectionDescription
circlesInMsgOpNavCirclesMsgPayloadInputDetected planet limb circle data
cameraConfigInMsgCameraConfigMsgPayloadInputCamera intrinsic parameters
attInMsgNavAttMsgPayloadInputSpacecraft attitude
navStateOutMsgNavTransMsgPayloadOutputEstimated position and velocity
filtDataOutMsgPixelLineFilterMsgPayloadOutputFull filter state including pixel/line biases
from Basilisk.fswAlgorithms import pixelLineBiasUKF

pixelFilter = pixelLineBiasUKF.pixelLineBiasUKF()
pixelFilter.ModelTag = "pixelLineBiasUKF"

pixelFilter.circlesInMsg.subscribeTo(houghCirclesMsg)
pixelFilter.cameraConfigInMsg.subscribeTo(cameraConfigMsg)
pixelFilter.attInMsg.subscribeTo(navAttMsg)
scSim.AddModelToTask(taskName, pixelFilter)
Use pixelLineBiasUKF when your camera has a significant, slowly-varying pixel or line bias that degrades relativeODuKF accuracy. The augmented state estimates and removes this bias online.

Fault detection (faultDetection)

Compares two independent OpNav measurement sources and produces a single fused or selected output. You configure a fault mode that determines how the two inputs are combined and how failures are handled.

Fault modes

ModeBehavior
0Least restrictive: uses whichever measurement is available; merges both when both are present.
1Moderate: uses the primary measurement when both are available; checks secondary for dissimilarity.
2Most restrictive: primary is only used when the secondary confirms it.
When both measurements are available and consistent, mode 0 fuses them using an inverse-covariance weighted average:
P = (P1⁻¹ + P2⁻¹)⁻¹
x = P (P1⁻¹ x1 + P2⁻¹ x2)

Messages

VariableTypeDirectionDescription
navMeasPrimaryInMsgOpNavMsgPayloadInputPrimary navigation measurement
navMeasSecondaryInMsgOpNavMsgPayloadInputSecondary navigation measurement
cameraConfigInMsgCameraConfigMsgPayloadInputCamera configuration
attInMsgNavAttMsgPayloadInputSpacecraft attitude
opNavOutMsgOpNavMsgPayloadOutputFused or selected navigation measurement
from Basilisk.fswAlgorithms import faultDetection

faultDet = faultDetection.FaultDetectionData()
faultDet.sigmaFault = 3    # covariance multiplier for fault trigger
faultDet.faultMode = 1     # use primary, check secondary

faultDet.navMeasPrimaryInMsg.subscribeTo(relativeODMsg)
faultDet.navMeasSecondaryInMsg.subscribeTo(pixelBiasMsg)
faultDet.cameraConfigInMsg.subscribeTo(cameraConfigMsg)
faultDet.attInMsg.subscribeTo(navAttMsg)
scSim.AddModelToTask(taskName, faultDet)
The sigmaFault parameter controls how far the two measurements must disagree (in units of their combined covariance) before a fault is declared. A value of 3 corresponds to a 3-sigma threshold.

Small-body navigation (EKF and UKF)

For proximity operations around small bodies, see the smallBodyNavEKF and smallBodyNavUKF modules documented in State estimation. Those filters jointly estimate spacecraft relative position, velocity, and the small body’s attitude and spin rate.

Build docs developers (and LLMs) love