ADCS.controller.plan_and_track.planner_settings module

class ADCS.controller.plan_and_track.planner_settings.PlannerSettings(est_sat, dt_control=1.0, pass1_config=None, pass2_config=None, cost_main=None, cost_second=None, cost_tvlqr=None, init_traj=None, dt_tvlqr=1, tvlqr_len=60, tvlqr_overlap=15, dt_tp=30.0, precalculation_time=100, traj_overlap=150, bdot_on=1, debug_plot_on=False, include_gg=False, include_resdipole=False, include_prop=False, include_drag=False, include_srp=False, include_gendist=False)[source]

Bases: object

Container class for all configuration parameters required by the trajectory planner.

This class aggregates physical parameters, solver configurations, actuator limits, cost weights, timing parameters, and disturbance models into a single interface consumed by the C++ trajectory planner.

Mathematically, the planner solves a constrained optimal control problem of the form

\[\min_{\mathbf{u}(t)} \; \int_{0}^{T} \ell\bigl(\mathbf{x}(t), \mathbf{u}(t)\bigr)\, dt + \ell_N\bigl(\mathbf{x}(T)\bigr)\]

subject to nonlinear rigid-body dynamics

\[\dot{\mathbf{x}} = f(\mathbf{x}, \mathbf{u}, \mathbf{d})\]

actuator saturation limits, and optional environmental disturbance torques \(\mathbf{d}\).

The settings in this class parameterize both the dynamics and the optimization algorithm, including multi-pass augmented Lagrangian iLQR configurations.

Parameters:
  • est_sat (EstimatedSatellite) – Estimated satellite model providing inertia, actuator definitions, state dimension, and disturbances.

  • dt_control (float) – Control update period in seconds.

  • pass1_config (SolverPassConfig) – Solver configuration for the first (exploration) optimization pass.

  • pass2_config (SolverPassConfig) – Solver configuration for the second (refinement) optimization pass.

  • cost_main (CostWeights) – Cost weights for the main optimization pass.

  • cost_second (CostWeights) – Cost weights for the second optimization pass.

  • cost_tvlqr (CostWeights) – Cost weights for time-varying LQR tracking.

  • init_traj (InitTrajConfig) – Initial trajectory generation configuration.

  • dt_tvlqr (float) – Time step for TVLQR controller discretization.

  • tvlqr_len (float) – Duration of each TVLQR segment in seconds.

  • tvlqr_overlap (float) – Overlap duration between consecutive TVLQR segments in seconds.

  • dt_tp (float) – Time step used by the trajectory planner.

  • precalculation_time (float) – Planning horizon precomputation time in seconds.

  • traj_overlap (float) – Overlap duration between planned trajectories.

  • bdot_on (int) – Flag enabling B-dot detumbling logic.

  • debug_plot_on (bool) – Flag enabling debug plotting.

  • include_gg (bool) – Flag enabling gravity-gradient disturbance modeling.

  • include_resdipole (bool) – Flag enabling residual dipole disturbance modeling.

  • include_prop (bool) – Flag enabling propulsion disturbance modeling.

  • include_drag (bool) – Flag enabling aerodynamic drag disturbance modeling.

  • include_srp (bool) – Flag enabling solar radiation pressure disturbance modeling.

  • include_gendist (bool) – Flag enabling generic disturbance torque modeling.

initTrajSettings()[source]

Return initial trajectory generation parameters.

These settings define how the initial guess trajectory is constructed prior to optimization, which can significantly affect convergence.

Returns:

Tuple containing initial trajectory configuration parameters.

Return type:

Tuple[float, float, Tuple, Tuple]

mainAlilqrSettings()[source]

Return solver settings for the first augmented Lagrangian iLQR pass.

The first pass prioritizes global exploration with a low penalty parameter and increased iteration limits, solving a relaxed constrained optimization problem.

Returns:

Tuple containing line search, augmented Lagrangian, convergence, and regularization settings.

Return type:

Tuple[Tuple, Tuple, Tuple, Tuple]

optMainCostSettings()[source]

Return cost weights for the main optimization pass.

The running and terminal costs are defined as

\[\ell = \mathbf{x}^\top \mathbf{Q} \mathbf{x} + \mathbf{u}^\top \mathbf{R} \mathbf{u}\]

with increased terminal penalties to emphasize goal convergence.

Returns:

Tuple encoding main-pass cost weights.

Return type:

Tuple

optSecondCostSettings()[source]

Return cost weights for the second optimization pass.

These weights may differ from the main pass to emphasize constraint satisfaction or control smoothing.

Returns:

Tuple encoding second-pass cost weights.

Return type:

Tuple

optTVLQRCostSettings(tracking_LQR_formulation)[source]

Return cost weights for the time-varying LQR controller.

The TVLQR controller minimizes a quadratic tracking cost

\[J = \int (\mathbf{x} - \mathbf{x}_r)^\top \mathbf{Q} (\mathbf{x} - \mathbf{x}_r) + \mathbf{u}^\top \mathbf{R} \mathbf{u} \, dt\]

where the formulation can be adjusted via the tracking flag.

Parameters:

tracking_LQR_formulation (int) – Integer flag selecting the tracking LQR formulation.

Returns:

Tuple encoding TVLQR cost weights.

Return type:

Tuple

planner_disturbance_settings()[source]

Return disturbance configuration parameters for the C++ planner.

Disturbance torques are modeled as additive inputs

\[\boldsymbol{\tau}_{\text{total}} = \boldsymbol{\tau}_{\text{control}} + \boldsymbol{\tau}_{\text{dist}}\]

where the disturbance torque may include aerodynamic drag, solar radiation pressure, gravity-gradient effects, propulsion torques, residual dipole effects, or generic disturbances.

Returns:

Tuple containing disturbance enable flags, SRP coefficients, drag coefficients, normalization factor, propulsion torque, generic disturbance torque, and residual dipole torque.

Return type:

Tuple[Tuple[bool, …], numpy.ndarray, numpy.ndarray, int,

numpy.ndarray, numpy.ndarray, numpy.ndarray]

secondAlilqrSettings()[source]

Return solver settings for the second augmented Lagrangian iLQR pass.

The second pass increases constraint penalties to enforce feasibility and refine the solution obtained from the first pass.

Returns:

Tuple containing line search, augmented Lagrangian, convergence, and regularization settings.

Return type:

Tuple[Tuple, Tuple, Tuple, Tuple]

systemSettings()[source]

Return system-level configuration parameters for the C++ planner.

These parameters define the rigid-body dynamics discretization and numerical tolerances used by the planner. The inertia matrix enters the rotational equations of motion

\[\mathbf{J}\dot{\boldsymbol{\omega}} = \boldsymbol{\tau} - \boldsymbol{\omega} \times (\mathbf{J}\boldsymbol{\omega})\]

where \(\mathbf{J}\) is the estimated inertia tensor.

Returns:

Tuple containing inertia matrix, trajectory planner time step, TVLQR time step, numerical epsilon, TVLQR segment length, and TVLQR overlap duration.

Return type:

Tuple[numpy.ndarray, float, float, float, float, float]