plannersettings#

Variables

static constexpr int MAX_OUTER_PASSES = 2#
struct InitTrajConfig#
#include <plannersettings.h>

Initial trajectory configuration.

Settings controlling how the initial control/state trajectory is generated before running the ALTRO optimization. The initialization can strongly affect convergence speed and robustness of the solver.

Param initcontroller:

Integer flag selecting which controller or strategy is used to generate the initial trajectory guess. Typical uses include zero-input rollout, PD control, or a custom warm-start controller.

Public Members

int initcontroller = 0#
struct DisturbanceConfig#
#include <plannersettings.h>

Disturbance modeling configuration.

Enables and parameterizes disturbance models that the optimizer accounts for during trajectory optimization. These disturbances are incorporated into the system dynamics or cost to improve robustness and realism.

Enabled disturbances may include:

  • Aerodynamic drag

  • Propulsion torques

  • Solar radiation pressure (SRP)

  • Gravity-gradient torque

  • Generic external torques

  • Residual magnetic dipole effects

Coefficient vectors represent linear scaling parameters used in disturbance models. If enabled, they are applied during forward rollout and linearization.

Param plan_for_aero:

Enable aerodynamic disturbance model

Param plan_for_prop:

Enable propulsion torque disturbance

Param plan_for_srp:

Enable solar radiation pressure disturbance

Param plan_for_gg:

Enable gravity-gradient disturbance

Param plan_for_gendist:

Enable generic disturbance torque

Param plan_for_resdipole:

Enable residual dipole torque

Param srp_coeff:

Solar radiation pressure coefficients

Param drag_coeff:

Aerodynamic drag coefficients

Param coeff_N:

Number of disturbance coefficients used in estimation

Param res_dipole:

Residual dipole torque vector

Param prop_torque:

Constant propulsion torque vector

Param gendist_torque:

Generic disturbance torque vector

Param J_est:

Estimated inertia matrix used for disturbance modeling

Public Members

bool plan_for_aero = false#
bool plan_for_prop = false#
bool plan_for_srp = false#
bool plan_for_gg = false#
bool plan_for_gendist = false#
bool plan_for_resdipole = false#
Eigen::Vector3d srp_coeff = Eigen::Vector3d::Zero()#
Eigen::Vector3d drag_coeff = Eigen::Vector3d::Zero()#
int coeff_N = 0#
Eigen::Vector3d res_dipole = Eigen::Vector3d::Zero()#
Eigen::Vector3d prop_torque = Eigen::Vector3d::Zero()#
Eigen::Vector3d gendist_torque = Eigen::Vector3d::Zero()#
Eigen::Matrix3d J_est = Eigen::Matrix3d::Zero()#
struct ConstraintConfig#
#include <plannersettings.h>

Constraint configuration.

Defines hard and soft constraints enforced during optimization. These are typically handled via the augmented Lagrangian framework inside ALTRO.

Constraints may include actuator limits, angular velocity bounds, and environmental pointing constraints (e.g., sun avoidance).

Param control_limit_scale:

Scaling factor applied to actuator limits

Param u_max:

Maximum control input vector

Param wmax:

Maximum allowable angular velocity magnitude (rad/s)

Param sun_limit_angle:

Minimum allowed angle to sun direction (rad)

Public Members

double control_limit_scale = 0.75#
Eigen::Matrix<double, Eigen::Dynamic, 1, 0, saltro::limits::MAX_CTRL_DIM, 1> u_max#

Stack-allocated bounded control limit vector (no heap allocation).

double wmax = 20.0 * M_PI / 180.0#
double sun_limit_angle = 20.0 * M_PI / 180.0#
struct CostConfig#
#include <plannersettings.h>

Cost function configuration.

Defines the weights and structure of the stage and terminal cost functions used in the ALTRO optimization. Costs typically penalize:

  • Orientation error

  • Angular velocity error

  • Control effort

  • Reaction wheel momentum

  • Actuator stiction or saturation

Stage costs are applied at each timestep:

\[ \ell_k = w_\theta e_\theta^2 + w_\omega e_\omega^2 + w_u \|\mathbf{u}_k\|^2 \]

Terminal costs are applied at the final timestep:

\[ \ell_N = w_\theta^N e_\theta^2 + w_\omega^N e_\omega^2 \]

Param angle:

Weight on orientation error

Param ang_vel:

Weight on angular velocity error

Param ang_vel_mag:

Weight on angular velocity magnitude

Param ang_vel_err_dir:

Weight on angular velocity direction error

Param control_mult:

Global multiplier on control cost

Param mtq_control_weight:

Magnetorquer control cost weight

Param rw_control_weight:

Reaction wheel control cost weight

Param magic_control_weight:

Additional actuator control weight

Param rw_AM_weight:

Reaction wheel angular momentum penalty

Param rw_stic_weight:

Reaction wheel stiction penalty

Param RWh_max_mult:

Multiplier when wheel momentum near saturation

Param RWh_stiction_mult:

Multiplier for stiction region

Param RWh_ok_mult:

Multiplier when wheel is within safe region

Param angle_N:

Terminal orientation weight

Param ang_vel_N:

Terminal angular velocity weight

Param ang_vel_mag_N:

Terminal angular velocity magnitude weight

Param ang_vel_err_dir_N:

Terminal angular velocity direction weight

Param ang_cost_func_type:

Type of orientation error cost function used

Param use_cost_hess:

If true, use analytic Hessians of cost

Public Members

double angle = 1e3#
double ang_vel = 1e4#
double ang_vel_mag = 0.0#
double ang_vel_err_dir = 0.0#
double control_mult = 1.0#
double mtq_control_weight = 1e3#
double rw_control_weight = 1e8#
double magic_control_weight = 0.0001#
double rw_AM_weight = 1e4#
double rw_stic_weight = 1.0#
double RWh_max_mult = 0.8#
double RWh_stiction_mult = 0.01#
double RWh_ok_mult = 0.5#
double angle_N = 1e4#
double ang_vel_N = 1e5#
double ang_vel_mag_N = 0.0#
double ang_vel_err_dir_N = 0.0#
int ang_cost_func_type = 2#
bool use_cost_hess = false#
struct AugLagConfig#
#include <plannersettings.h>

Augmented Lagrangian configuration.

Controls the outer-loop constraint handling in ALTRO using an augmented Lagrangian method. Constraints are enforced by iteratively updating penalty parameters and Lagrange multipliers:

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

Param max_outer_iters:

Maximum number of outer iterations

Param lag_mult_init:

Initial Lagrange multiplier value

Param lag_mult_max:

Maximum allowed Lagrange multiplier

Param penalty_init:

Initial penalty parameter

Param penalty_max:

Maximum penalty parameter

Param penalty_scale:

Multiplicative increase per iteration

Param constraint_tol:

Constraint satisfaction tolerance

Param total_cost_tol:

Total cost convergence tolerance

Public Members

int max_outer_iters = 30#
double lag_mult_init = 0.0#
double lag_mult_max = 1e20#
double penalty_init = 1e-1#
double penalty_max = 1e16#
double penalty_scale = 10.0#
double constraint_tol = 0.002#
double total_cost_tol = 1e-2#
struct ILQRConfig#
#include <plannersettings.h>

iLQR inner-loop configuration.

Settings for the inner iterative LQR solver used by ALTRO to optimize trajectories between augmented Lagrangian updates.

The solver iteratively linearizes dynamics and quadratizes costs:

\[ \mathbf{x}_{k+1} \approx f(\mathbf{x}_k,\mathbf{u}_k) \]

Param max_iters:

Maximum number of iLQR iterations

Param grad_tol:

Gradient norm convergence tolerance

Param cost_tol:

Cost improvement tolerance

Param z_count_lim:

Maximum number of zero-improvement steps

Param max_cost:

Abort if cost exceeds this value

Param state_bound:

Maximum allowed state magnitude

Public Members

int max_iters = 250#
double grad_tol = 1e-3#
double cost_tol = 1e-1#
int z_count_lim = 10#
double max_cost = 1e40#
double state_bound = 10.0#
struct RegularizationConfig#
#include <plannersettings.h>

Regularization configuration.

Controls Levenberg–Marquardt-style regularization used to ensure numerical stability when solving Riccati equations and backward passes.

Regularization modifies the Hessian:

\[ Q_{uu} \leftarrow Q_{uu} + \rho I \]

Param reg_init:

Initial regularization value

Param reg_min:

Minimum regularization

Param reg_max:

Maximum regularization

Param reg_scale:

Multiplicative scaling factor

Param reg_bump:

Factor used when increasing regularization

Param reg_min_cond:

Minimum condition threshold

Param rand_add_ratio:

Random diagonal perturbation ratio

Param use_dynamics_hess:

Use second derivatives of dynamics

Param use_constraint_hess:

Use second derivatives of constraints

Public Members

double reg_init = 1e-2#
double reg_min = 1e-8#
double reg_max = 1e30#
double reg_scale = 1.6#
double reg_bump = 10.0#
int reg_min_cond = 2#
double rand_add_ratio = 0.0#
bool use_dynamics_hess = false#
bool use_constraint_hess = false#
struct LineSearchConfig#
#include <plannersettings.h>

Line search configuration.

Parameters for backtracking line search used during forward rollout. The step size \(\alpha\) is reduced until sufficient decrease is achieved:

\[ J(\alpha) \le J(0) + \beta_1 \alpha \nabla J^\top d \]

Param max_iters:

Maximum line search iterations

Param beta1:

Sufficient decrease parameter

Param beta2:

Maximum allowable cost increase factor

Public Members

int max_iters = 20#
double beta1 = 1e-10#
double beta2 = 500.0#
struct PassConfig#
#include <plannersettings.h>

Per-pass optimization configuration.

Each ALTRO outer pass may use different cost weights, regularization, or time discretization. This allows coarse-to-fine optimization strategies.

Param cost:

Cost configuration for this pass

Param auglag:

Augmented Lagrangian configuration

Param ilqr:

iLQR configuration

Param reg:

Regularization configuration

Param linesearch:

Line search configuration

Param dt:

Timestep used for discretization

Public Members

CostConfig cost#
AugLagConfig auglag#
ILQRConfig ilqr#
RegularizationConfig reg#
LineSearchConfig linesearch#
double dt = 1.0#
struct TVLQRSettings#
#include <plannersettings.h>

TVLQR gain-generation configuration.

Controls the backward-pass discretization and chunking window used when generating tracking gains from an optimized trajectory.

Param dt_tvlqr:

Fixed TVLQR gain discretization step. SALTRO currently uses the planner pass dt and keeps this at 0.0.

Param tvlqr_len:

Chunk duration in seconds for gain computation.

Param tvlqr_overlap:

Overlap duration in seconds between consecutive chunks.

Public Functions

inline TVLQRSettings()#

Public Members

double dt_tvlqr#
double tvlqr_len = 60.0#
double tvlqr_overlap = 15.0#
struct PlannerSettings#
#include <plannersettings.h>

Top-level planner settings.

Aggregates all configuration parameters required by the ALTRO optimizer. Multiple passes can be executed sequentially, each refining the trajectory.

Typical workflow:

  1. Initialize trajectory

  2. Run ALTRO passes

  3. Update penalties and constraints

  4. Return optimized trajectory

Param constraints:

Constraint configuration

Param disturbances:

Disturbance modeling configuration

Param init_traj:

Initial trajectory configuration

Param num_passes:

Number of optimization passes

Param passes:

Array of pass-specific configurations

Public Members

ConstraintConfig constraints#
DisturbanceConfig disturbances#
InitTrajConfig init_traj#
TVLQRSettings tvlqr#
int num_passes = 0#
std::array<PassConfig, MAX_OUTER_PASSES> passes#