ADCS.controller.plan_and_track.planner_subsettings module

class ADCS.controller.plan_and_track.planner_subsettings.AugLagConfig(lag_mult_init=0.0, lag_mult_max=1e+20, penalty_init=0.1, penalty_max=1e+16, penalty_scale=10.0)[source]

Bases: object

Configuration for augmented Lagrangian constraint handling.

The augmented Lagrangian formulation transforms a constrained problem

\[\min_x J(x) \quad \text{s.t.} \quad c(x) = 0\]

into an unconstrained sequence of problems by augmenting the cost:

\[\mathcal{L}_A(x, \lambda, \mu) = J(x) + \lambda^\top c(x) + \frac{\mu}{2}\|c(x)\|^2\]

where \(\lambda\) are Lagrange multipliers and \(\mu\) is the penalty parameter.

Parameters:
  • lag_mult_init (float) – Initial Lagrange multiplier value.

  • lag_mult_max (float) – Maximum allowed magnitude of Lagrange multipliers.

  • penalty_init (float) – Initial penalty parameter.

  • penalty_max (float) – Maximum penalty parameter.

  • penalty_scale (float) – Multiplicative factor used to increase the penalty.

to_tuple()[source]
Return type:

Tuple[float, float, float, float, float]

lag_mult_init: float = 0.0
lag_mult_max: float = 1e+20
penalty_init: float = 0.1
penalty_max: float = 1e+16
penalty_scale: float = 10.0
class ADCS.controller.plan_and_track.planner_subsettings.ConvergenceConfig(max_outer_iter=30, max_inner_iter=250, max_total_iter=7000, grad_tol=0.001, ilqr_cost_tol=0.1, total_cost_tol=0.01, z_count_lim=10, c_max=0.002, max_cost=1e+40, xmax_val=10.0)[source]

Bases: object

Configuration for convergence criteria and iteration limits.

The optimization uses nested iterations:

  • Outer loop for augmented Lagrangian updates

  • Inner loop for iLQR refinement

Convergence is declared when cost reduction and constraint violations satisfy specified tolerances.

Parameters:
  • max_outer_iter (int) – Maximum number of augmented Lagrangian iterations.

  • max_inner_iter (int) – Maximum number of iLQR iterations per outer loop.

  • max_total_iter (int) – Absolute maximum number of iterations.

  • grad_tol (float) – Gradient norm tolerance.

  • ilqr_cost_tol (float) – Cost change tolerance for inner loop convergence.

  • total_cost_tol (float) – Cost change tolerance for outer loop convergence.

  • z_count_lim (int) – Maximum number of consecutive small-decrease iterations.

  • c_max (float) – Maximum allowable constraint violation.

  • max_cost (float) – Cost threshold for divergence detection.

  • xmax_val (float) – State magnitude bound for divergence detection.

to_tuple(state_len)[source]
Parameters:

state_len (int)

Return type:

Tuple[int, int, int, float, float, float, int, float, float, ndarray[tuple[int, …], dtype[float64]]]

c_max: float = 0.002
grad_tol: float = 0.001
ilqr_cost_tol: float = 0.1
max_cost: float = 1e+40
max_inner_iter: int = 250
max_outer_iter: int = 30
max_total_iter: int = 7000
total_cost_tol: float = 0.01
xmax_val: float = 10.0
z_count_lim: int = 10
class ADCS.controller.plan_and_track.planner_subsettings.CostWeights(angle=1000.0, ang_vel=10000.0, control_mult=1.0, ang_vel_mag=0.0, ang_vel_err_dir=0.0, angle_N=10000.0, ang_vel_N=100000.0, ang_vel_mag_N=0.0, ang_vel_err_dir_N=0.0, ang_cost_func_type=2, use_raw_control_cost=True, consider_vector_in_tvlqr=0, use_full_cost_hessian=False)[source]

Bases: object

Cost function weights for trajectory optimization.

The discrete-time cost function minimized by the planner is

\[J = \sum_{k=0}^{N-1} \left( \mathbf{x}_k^\top \mathbf{Q} \mathbf{x}_k + \mathbf{u}_k^\top \mathbf{R} \mathbf{u}_k \right) + \mathbf{x}_N^\top \mathbf{Q}_N \mathbf{x}_N\]

where running and terminal costs may differ.

Parameters:
  • angle (float) – Running attitude error weight.

  • ang_vel (float) – Running angular velocity weight.

  • control_mult (float) – Multiplier applied to actuator control costs.

  • ang_vel_mag (float) – Running cost on angular velocity projected onto magnetic field.

  • ang_vel_err_dir (float) – Running cost on angular velocity along error direction.

  • angle_N (float) – Terminal attitude error weight.

  • ang_vel_N (float) – Terminal angular velocity weight.

  • ang_vel_mag_N (float) – Terminal magnetic-field angular velocity weight.

  • ang_vel_err_dir_N (float) – Terminal angular velocity error-direction weight.

  • ang_cost_func_type (int) – Attitude cost formulation selector.

  • use_raw_control_cost (bool) – Flag selecting raw or scaled control costs.

  • consider_vector_in_tvlqr (int) – Flag enabling vector tracking in TVLQR.

  • use_full_cost_hessian (bool) – Flag enabling full Newton cost Hessian.

to_tuple(tracking_formulation=None)[source]

Convert to tuple for C++ interface.

Parameters:

tracking_formulation (int | None) – If provided, returns TVLQR cost settings format. If None, returns main/second pass format.

Return type:

Tuple[float, …]

ang_cost_func_type: int = 2
ang_vel: float = 10000.0
ang_vel_N: float = 100000.0
ang_vel_err_dir: float = 0.0
ang_vel_err_dir_N: float = 0.0
ang_vel_mag: float = 0.0
ang_vel_mag_N: float = 0.0
angle: float = 1000.0
angle_N: float = 10000.0
consider_vector_in_tvlqr: int = 0
control_mult: float = 1.0
use_full_cost_hessian: bool = False
use_raw_control_cost: bool = True
class ADCS.controller.plan_and_track.planner_subsettings.InitTrajConfig(bdot_gain=1000.0, hl_angle_limit=0.17453292519943295, high_settings=(0, -2.0, 0, 0.0, 0.0, 0.5), low_settings=(0, -2.0, 0, 0.0, 0.0, 0.5))[source]

Bases: object

Configuration for initial trajectory generation.

The initial guess trajectory may use B-dot detumbling and heuristic saturation limits to provide a dynamically feasible starting point for optimization.

Parameters:
  • bdot_gain (float) – Gain used for B-dot detumbling initialization.

  • hl_angle_limit (float) – High-level angle threshold for switching strategies.

  • high_settings (tuple) – Tuple defining high-level initialization parameters.

  • low_settings (tuple) – Tuple defining low-level initialization parameters.

to_tuple()[source]
Return type:

Tuple[float, float, tuple, tuple]

bdot_gain: float = 1000.0
high_settings: tuple = (0, -2.0, 0, 0.0, 0.0, 0.5)
hl_angle_limit: float = 0.17453292519943295
low_settings: tuple = (0, -2.0, 0, 0.0, 0.0, 0.5)
class ADCS.controller.plan_and_track.planner_subsettings.LineSearchConfig(max_iters=20, beta1=1e-10, beta2=500.0)[source]

Bases: object

Configuration for backtracking line search in the iLQR forward pass.

During the forward rollout, a step size \(\alpha\) is chosen to ensure sufficient decrease of the cost function. Let

\[z = \frac{J_{\text{actual}} - J_{\text{new}}}{J_{\text{expected}}}\]

where \(J_{\text{expected}}\) is the quadratic model prediction. The step is accepted if

\[\beta_1 < z < \beta_2\]

which prevents both excessively small steps and steps that violate the local quadratic approximation.

Parameters:
  • max_iters (int) – Maximum number of line search iterations.

  • beta1 (float) – Lower bound on acceptable cost decrease ratio.

  • beta2 (float) – Upper bound on acceptable cost decrease ratio.

to_tuple()[source]
Return type:

Tuple[int, float, float]

beta1: float = 1e-10
beta2: float = 500.0
max_iters: int = 20
class ADCS.controller.plan_and_track.planner_subsettings.RegularizationConfig(reg_init=0.01, reg_min=1e-08, reg_max=1e+30, reg_scale=1.6, reg_bump=10.0, reg_min_cond=2, rand_add_ratio=0.0, use_dynamics_hess=0, use_constraint_hess=0)[source]

Bases: object

Configuration for Levenberg–Marquardt regularization in the backward pass.

To compute feedback gains, the control Hessian \(\mathbf{Q}_{uu}\) must be positive definite. When it is ill-conditioned or indefinite, regularization modifies it as

\[\mathbf{Q}_{uu}^{\text{reg}} = \mathbf{Q}_{uu} + \rho \mathbf{I}\]

where \(\rho\) is adapted during optimization.

Parameters:
  • reg_init (float) – Initial regularization parameter.

  • reg_min (float) – Minimum allowable regularization value.

  • reg_max (float) – Maximum allowable regularization value.

  • reg_scale (float) – Factor used to scale regularization up or down.

  • reg_bump (float) – Additional increase applied after failed line search.

  • reg_min_cond (int) – Condition flag controlling minimum regularization enforcement.

  • rand_add_ratio (float) – Ratio of random noise added to escape local minima.

  • use_dynamics_hess (int) – Flag enabling second-order dynamics terms.

  • use_constraint_hess (int) – Flag enabling second-order constraint terms.

to_tuple()[source]
Return type:

Tuple[float, float, float, float, float, int, float, int, int]

rand_add_ratio: float = 0.0
reg_bump: float = 10.0
reg_init: float = 0.01
reg_max: float = 1e+30
reg_min: float = 1e-08
reg_min_cond: int = 2
reg_scale: float = 1.6
use_constraint_hess: int = 0
use_dynamics_hess: int = 0
class ADCS.controller.plan_and_track.planner_subsettings.SolverPassConfig(line_search=<factory>, aug_lag=<factory>, convergence=<factory>, regularization=<factory>)[source]

Bases: object

Aggregate configuration for a single optimization pass.

This class bundles line search, augmented Lagrangian, convergence, and regularization settings into a single structure used by the solver.

Parameters:
aug_lag: AugLagConfig
convergence: ConvergenceConfig
regularization: RegularizationConfig