22#include <MatrixLib/MatrixLib.h>
28ml_matrix
momentum_unloading(
const ml_matrix& u,
const ml_matrix& b,
double gain,
const ml_matrix& h,
double tol = 0.2 );
30ml_matrix
momentum_with_rwa_body(
const ml_matrix& inr,
const ml_matrix& omega_body,
const ml_matrix& omega_rwa,
const ml_matrix& u_rwa,
double inr_rwa );
32ml_matrix
magnetic_control(
const ml_matrix& torque_demand,
const ml_matrix& u_magnetic_torquer,
const ml_matrix& b_field,
double cost );
ml_matrix discrete_state_transition_matrix(const ml_matrix &w, double dT)
State transition matrix.
Definition: sc_control.cc:26
ml_matrix attitude_propagation_discrete(const ml_matrix &w, const ml_matrix &q, double dT)
State propagation.
Definition: sc_control.cc:53
ml_matrix magnetic_control(const ml_matrix &torque_demand, const ml_matrix &u_magnetic_torquer, const ml_matrix &b_field, double cost)
Magnetic torquer control.
Definition: sc_control.cc:168
ml_matrix momentum_with_rwa_body(const ml_matrix &inr, const ml_matrix &omega_body, const ml_matrix &omega_rwa, const ml_matrix &u_rwa, double inr_rwa)
Momentum with RWA in the body frame.
Definition: sc_control.cc:159
ml_matrix momentum_unloading(const ml_matrix &u, const ml_matrix &b, double gain, const ml_matrix &h, double tol=0.2)
Momentum management using magnetic torquers.
Definition: sc_control.cc:96