API Reference

RunwayLib.CameraConfigType
struct CameraConfig{S} <: RunwayLib.AbstractCameraConfig{S}

Camera configuration with reference frame S being either :offset or :centered. Check Camera Model for further explanation.

Fields

  • focal_length_px::Unitful.Quantity{Float64, NoDims, Unitful.FreeUnits{(pixel,), NoDims, nothing}}

  • image_width::Unitful.Quantity{Float64, NoDims, Unitful.FreeUnits{(pixel,), NoDims, nothing}}

  • image_height::Unitful.Quantity{Float64, NoDims, Unitful.FreeUnits{(pixel,), NoDims, nothing}}

Examples

using RunwayLib, Unitful.DefaultSymbols, Rotations
cam_pos = WorldPoint(-10m, 0m, 0m)
cam_rot = RotZYX(zeros(3)...)
world_pt = WorldPoint(0m, 0m, 0m)

focal_length = 25mm
pixel_size = 5μm/px
camconf_centered = CameraConfig{:centered}(focal_length, pixel_size, 4096.0px, 2048.0px)
project(cam_pos, cam_rot, world_pt, camconf_centered); nothing
source
RunwayLib.CameraConfigMethod
CameraConfig{S}(
    focal_length::WithDims(mm), pixel_size::WithDims(mm / px),
    image_width::WithDims(px), image_height::WithDims(px)
)

Convenience constructor for CameraConfig taking focal length and pixel size separately.

source
RunwayLib.CameraMatrixType
struct CameraMatrix{S,T<:WithDims(px)} <: AbstractCameraConfig{S}

Camera model using 3x3 projection matrix with uniform pixel units. The reference frame S can either be :offset or :centered. See Camera Model for more explanation.

Note

Notably it is the user's responsibility to construct the matrix such that the axes are aligned correctly, i.e., for S=:offset the first two offdiagonal elements must be negative.

Warning

At this time, only S = :offset is implemented.

Examples

using StaticArrays, RunwayLib
f_px = 5e6px  # focal length in pixels
cx, cy = 2048px, 1024px
matrix = SA[
    -f_px   0px  cx
    0px   -f_px  cy
    0px   0px   1px
]
CameraMatrix{:offset}(matrix, 2cx, 2cy); nothing

Related Functions

See also project.

source
RunwayLib.CameraPointType
CameraPoint{T} <: FieldVector{3, T}

Point in camera coordinate system.

Fields

  • x::T: Camera forward direction (positive towards scene)
  • y::T: Camera right direction (positive to the right)
  • z::T: Camera down direction (positive downward)

Units

Typically uses meters (u"m") for all coordinates.

Coordinate System Convention

  • X-axis: Forward (into the scene)
  • Y-axis: Right (to the right of the camera)
  • Z-axis: Down (downward from camera)

This follows the standard computer vision convention.

Examples

# Point 10m in front of camera, 2m to the right, 1m below
cp = CameraPoint(10.0u"m", 2.0u"m", 1.0u"m")

# Access coordinates
println("Forward: ", cp.x)
println("Right: ", cp.y)
println("Down: ", cp.z)
source
RunwayLib.LineFeaturesType
LineFeatures{T, T′′, S, WL, OL, CC, M, M′}

Line feature observations and noise model for pose estimation.

Fields

  • world_line_endpoints: Vector of pairs of WorldPoints defining lines in world space
  • observed_lines: Vector of Line objects (r, theta) from observations
  • camconfig: Camera configuration
  • cov: Covariance matrix for observation errors
  • Linv: Inverted lower triangular part of covariance
source
RunwayLib.OptimizationConfigType
OptimizationConfig

Configuration parameters for pose estimation optimization.

Fields

  • max_iterations::Int: Maximum number of optimization iterations
  • convergence_tolerance: Convergence tolerance for residual norm
  • step_tolerance: Minimum step size tolerance
  • gradient_tolerance: Gradient norm tolerance for convergence

Examples

config = OptimizationConfig(
    max_iterations = 100,
    convergence_tolerance = 1e-6*1pixel,
    step_tolerance = 1e-8,
    gradient_tolerance = 1e-6
)
source
RunwayLib.PointFeaturesType
PointFeatures{T, T′, T′′, S, RC, OC, CC, M, M′}

Point feature observations and noise model for pose estimation.

source
RunwayLib.PoseEstimateType
PoseEstimate

Complete pose estimate with position, attitude, uncertainty, and convergence information.

Fields

  • position::WorldPoint: Estimated aircraft position in world coordinates
  • attitude::RotZYX: Estimated aircraft attitude (yaw, pitch, roll)
  • uncertainty::MvNormal: Joint position-attitude uncertainty distribution
  • residual_norm: Final residual norm from optimization (with units)
  • converged::Bool: Whether optimization converged successfully

Examples

# Create pose estimate
position = WorldPoint(500.0u"m", 10.0u"m", 100.0u"m")
attitude = RotZYX(0.1, 0.05, 0.02)  # Small attitude angles
uncertainty = MvNormal(zeros(6), I(6))  # 6-DOF uncertainty
residual_norm = 0.5*1pixel
converged = true

pose_est = PoseEstimate(position, attitude, uncertainty, residual_norm, converged)

# Access components
println("Position: ", pose_est.position)
println("Attitude: ", pose_est.attitude)
println("Converged: ", pose_est.converged)
source
RunwayLib.ProjectionPointType
ProjectionPoint{T, S} <: FieldVector{2, T}

Point in image projection coordinate system.

Type Parameters

  • T: Numeric type for coordinates
  • S: Coordinate system type (only :offset supported)

Fields

  • x::T: Image x-coordinate (horizontal pixel position)
  • y::T: Image y-coordinate (vertical pixel position)

Units

Typically uses pixels (1pixel) for coordinates.

Coordinate System Convention

For :offset coordinates:

  • Origin at top-left corner of image
  • X-axis: Horizontal (positive to the right)
  • Y-axis: Vertical (positive downward)

Examples

# Offset coordinates (origin at top-left)
pp_offset = ProjectionPoint{Float64, :offset}(1024.0*1pixel, 768.0*1pixel)

# Access coordinates
println("X: ", pp_offset.x)
println("Y: ", pp_offset.y)
source
RunwayLib.WorldPointType
WorldPoint{T} <: FieldVector{3, T}

Point in world coordinate system (runway-relative).

Fields

  • x::T: Along-track distance (positive towards far end of runway)
  • y::T: Cross-track distance (positive towards right side of runway)
  • z::T: Height above runway surface (positive upward)

Units

Typically uses meters (u"m") for all coordinates.

Examples

# Create a point 500m before runway threshold, 10m right of centerline, 100m high
wp = WorldPoint(-500.0u"m", 10.0u"m", 100.0u"m")

# Access coordinates
println("Along-track: ", wp.x)
println("Cross-track: ", wp.y) 
println("Height: ", wp.z)

# Arithmetic operations
wp2 = WorldPoint(100.0u"m", 0.0u"m", 50.0u"m")
wp_sum = wp + wp2  # Element-wise addition
wp_scaled = 2.0 * wp  # Scalar multiplication
source
Base.invMethod
inv(L::LowerTriangular{T, <:SMatrix}) where T

Custom inverse for lower triangular static matrices using forward-substitution. Preserves SMatrix type instead of converting to Matrix.

source
Base.invMethod
inv(U::UpperTriangular{T, <:SMatrix}) where T

Custom inverse for upper triangular static matrices using back-substitution. Preserves SMatrix type instead of converting to Matrix.

source
RunwayLib.WithDimsMethod
WithDims(q::Quantity)
WithDims(u::Units)

Returns a subtype of Unitful.Quantity with the dimensions constrained to the dimension of q or u. Useful to build unitful interfaces that don't constrain the numeric type or the unit, just the dimension of a quantity. Examples:

julia> using Unitful, Unitful.DefaultSymbols; import Unitful.hr

julia> using RunwayLib: WithDims

julia> circumference_of_square(side::WithDims(m)) = 4*side;

julia> circumference_of_square((1//2)m)  # works
2//1 m

julia> circumference_of_square((1//2)km)  # also works
2//1 km

julia> # You can also constrain the return type. The numeric type is usually inferred automatically.

julia> kinetic_energy(mass::WithDims(kg), velocity::WithDims(m/s))::WithDims(J) = mass*velocity^2;

julia> kinetic_energy(1000kg, 100km/hr)
10000000 kg km^2 hr^-2

See also WithUnits.

source
RunwayLib.WithUnitsMethod
WithUnits(q::Quantity)
WithUnits(u::Units)

Returns a subtype of Unitful.Quantity with the dimensions and units constrained to the dimension and units of q or u. Useful to build unitful interfaces that don't constrain the unit, but not the numeric type of a quantity. Examples:

julia> using Unitful, Unitful.DefaultSymbols; import Unitful.hr

julia> using RunwayLib: WithUnits

julia> circumference_of_square(side::WithUnits(m)) = 4*side;

julia> circumference_of_square((1//2)m)  # works
2//1 m

julia> # circumference_of_square((1//2)km)  # doesn't work, constrained to exactly meters

julia> # You can also constrain the return type. The numeric type is usually inferred automatically.

julia> kinetic_energy(mass::WithUnits(kg), velocity::WithUnits(m/s))::WithUnits(J) = mass*velocity^2 |> x->uconvert(J, x);

julia> kinetic_energy(1000kg, uconvert(m/s, 100km/hr))
62500000//81 J

See also WithDims.

source
RunwayLib.cam_pt_to_world_ptMethod
cam_pt_to_world_pt(cam_pos::WorldPoint, R::RotZYX, cam_pt::CameraPoint) -> WorldPoint

Transform a point from camera coordinates to world coordinates.

Arguments

  • cam_pos::WorldPoint: Camera position in world coordinates
  • cam_rot::RotZYX: Camera orientation (ZYX Euler angles: yaw, pitch, roll)
  • cam_pt::CameraPoint: Point to transform in camera coordinates

Returns

  • WorldPoint: Point in world coordinate system

Algorithm

  1. Rotate point by camera rotation to get world-relative coordinates
  2. Translate by camera position to get absolute world coordinates

Examples

using RunwayLib, Unitful.DefaultSymbols, Rotations
# Transform camera point back to world coordinates
cam_pos = WorldPoint(10.0m, 20m, 30m)
cam_rot = RotZYX(roll=0.0rad, pitch=0rad, yaw=0rad)  # No rotation
cam_pt = CameraPoint(1.0m, 2m, 3m)

world_pt = cam_pt_to_world_pt(cam_pos, cam_rot, cam_pt)

# output

3-element WorldPoint{Float64{m}} with indices SOneTo(3):
 11.0 m
 22.0 m
 33.0 m
source
RunwayLib.compute_integrity_statisticFunction
compute_integrity_statistic(cam_pos, cam_rot, pf::PointFeatures, lf::LineFeatures=NO_LINES; n_parameters=6)

Run the integrity check described in [1]. We can use this for runtime assurance to judge whether the measurements and uncertainties are consistent with the parameters of the problem.

Arguments

  • cam_pos: Camera position (WorldPoint)
  • cam_rot: Camera rotation (RotZYX)
  • pf: Point features with observations and covariance
  • lf: Line features with observations and covariance (default: NO_LINES)
  • n_parameters: Number of pose parameters (default 6 for full 6-DOF)

Returns

NamedTuple containing

  • stat: The RAIM-adaptation statistic;
  • p_value: p-value of Null-hypothesis. If this drops below, say, 5% then we can "reject", i.e., have a failure;
  • dofs: degrees of freedom (for Χ² distribution); and
  • residual_norm: norm of the whitened residual vector.

See also

WorldPoint, RotZYX, PointFeatures, LineFeatures.

source
RunwayLib.compute_worst_case_fault_direction_and_slopeMethod
compute_worst_case_fault_direction_and_slope(
    alpha_idx::Int,
    fault_indices::AbstractVector{Int},
    H::AbstractMatrix,
    noise_cov::AbstractMatrix,
)

Computes the worst-case fault direction and corresponding failure mode slope for a selected pose parameter and fault subset.

Arguments

  • alpha_idx::Int: Monitored parameter index
    • 1 = along-track position
    • 2 = cross-track position
    • 3 = height above runway
    • 4 = yaw
    • 5 = pitch
    • 6 = roll
  • fault_indices::AbstractVector{Int}: Indices of measurements in fault subset
  • H::AbstractMatrix: Jacobian matrix (ndof columns)
  • noise_cov::AbstractMatrix: Measurement noise covariance matrix

Returns

  • f_dir: Worst-case fault direction (normalized vector)
  • g_slope: Failure mode slope (quantifies sensitivity to faults in this direction)
Note

The Jacobian H must have the correct number of columns for the degrees of freedom (3 for position-only, 6 for full pose estimation).

source
RunwayLib.getlineMethod
getline(p1::ProjectionPoint, p2::ProjectionPoint) -> Line

Convert two projection points to Hough transform parameters (r, theta). Line represented as: r = xcos(theta) + ysin(theta)

source
RunwayLib.pose_optimization_objectiveMethod
pose_optimization_objective(pose_params, ps)

Unified optimization function for pose estimation.

Arguments

  • pose_params: Vector of pose parameters
    • [x, y, z, roll, pitch, yaw] for 6-DOF
    • [x, y, z] for 3-DOF
  • ps: PoseOptimizationParams6DOF or PoseOptimizationParams3DOF

Returns

  • Weighted reprojection error vector combining point and line features
source
RunwayLib.pose_optimization_objective_pointsMethod
pose_optimization_objective_points(cam_pos, cam_rot, point_features)

Compute weighted point feature residuals.

Arguments

  • cam_pos: Camera position (WorldPoint)
  • cam_rot: Camera rotation (Rotation)
  • point_features: PointFeatures struct

Returns

  • Weighted reprojection error vector
source
RunwayLib.projectMethod
function project(
    cam_pos::WorldPoint{T}, cam_rot::RotZYX, world_pt::WorldPoint{T′},
    camconfig::CameraConfig{S}=CAMERA_CONFIG_OFFSET
) where {T,T′,S}

Project 3D world point to 2D image coordinates using pinhole camera model. See Camera Model for more information.

source
RunwayLib.projectMethod
function project(
    cam_pos::WorldPoint{T}, cam_rot::RotZYX, world_pt::WorldPoint{T′},
    camconfig::CameraMatrix{S,U}
) where {T,T′,S,U}

Version dispatching on CameraMatrix.

source
RunwayLib.world_pt_to_cam_ptMethod
world_pt_to_cam_pt(cam_pos::WorldPoint, R::RotZYX, world_pt::WorldPoint) -> CameraPoint

Transform a point from world coordinates to camera coordinates.

Arguments

  • cam_pos::WorldPoint: Camera position in world coordinates
  • cam_rot::RotZYX: Camera orientation (ZYX Euler angles: yaw, pitch, roll)
  • world_pt::WorldPoint: Point to transform in world coordinates

Returns

  • CameraPoint: Point in camera coordinate system

Algorithm

  1. Translate point relative to camera position
  2. Rotate by inverse of camera rotation to get camera-relative coordinates

Examples

using RunwayLib, Unitful.DefaultSymbols, Rotations
# Camera at origin with no rotation
cam_pos = WorldPoint(0.0m, 0m, 0m)
cam_rot = RotZYX(roll=0.0rad, pitch=0rad, yaw=0rad)  # No rotation
world_pt = WorldPoint(1.0m, 2m, 3m)

cam_pt = world_pt_to_cam_pt(cam_pos, cam_rot, world_pt)

# output

3-element WorldPoint{Float64{m}} with indices SOneTo(3):
 1.0 m
 2.0 m
 3.0 m

With some rotation:

# Camera with 90-degree yaw rotation
cam_rot = RotZYX(yaw=π/2rad, roll=0.0rad, pitch=0.0rad)  # 90-degree yaw
world_pt = WorldPoint(1.0m, 0.0m, 0.0m)

cam_pt = world_pt_to_cam_pt(cam_pos, cam_rot, world_pt)
# After rotation, x becomes -y in camera frame
cam_pt ≈ WorldPoint(0.0m, -1.0m, 0.0m)

# output

true
source