- 3.0.2 optimal control module.
|
Go to the source code of this file.
Functions | |
template<size_t state_dim, size_t control_dim> | |
void | printSolution (const ct::core::StateVectorArray< state_dim > &x, const ct::core::ControlVectorArray< control_dim > &u, const ct::core::FeedbackArray< state_dim, control_dim > &K) |
template<size_t state_dim, size_t control_dim> | |
void | assertControlBounds (const ct::core::ControlVectorArray< control_dim > &u, const Eigen::VectorXi sparsity, const Eigen::VectorXd u_lb, const Eigen::VectorXd u_ub) |
check that control bounds are respected More... | |
template<size_t state_dim, size_t control_dim> | |
void | assertStateBounds (const ct::core::StateVectorArray< state_dim > &x, const Eigen::VectorXi sparsity, const Eigen::VectorXd x_lb, const Eigen::VectorXd x_ub) |
check that state bounds are respected More... | |
template<size_t state_dim, size_t control_dim, typename LINEAR_SYSTEM > | |
void | boxConstraintsTest (ct::core::ControlVector< control_dim > u0, ct::core::StateVector< state_dim > x0, ct::core::StateVector< state_dim > xf, int nb_u, Eigen::VectorXd u_lb, Eigen::VectorXd u_ub, Eigen::VectorXi u_box_sparsity, int nb_x, Eigen::VectorXd x_lb, Eigen::VectorXd x_ub, Eigen::VectorXi x_box_sparsity) |
template<size_t state_dim, size_t control_dim, typename LINEAR_SYSTEM > | |
void | generalConstraintsTest (ct::core::ControlVector< control_dim > u0, ct::core::StateVector< state_dim > x0, ct::core::StateVector< state_dim > xf, Eigen::VectorXd d_lb, Eigen::VectorXd d_ub, Eigen::MatrixXd C, Eigen::MatrixXd D) |
TEST (ConstrainedLQOCSolverTest, BoxConstrTest_small) | |
TEST (ConstrainedLQOCSolverTest, BoxConstrTest_medium) | |
TEST (ConstrainedLQOCSolverTest, GeneralConstrTest_small) | |
TEST (ConstrainedLQOCSolverTest, GeneralConstrTest_medium) | |
TEST (ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) | |
Variables | |
bool | verbose = false |
void printSolution | ( | const ct::core::StateVectorArray< state_dim > & | x, |
const ct::core::ControlVectorArray< control_dim > & | u, | ||
const ct::core::FeedbackArray< state_dim, control_dim > & | K | ||
) |
void assertControlBounds | ( | const ct::core::ControlVectorArray< control_dim > & | u, |
const Eigen::VectorXi | sparsity, | ||
const Eigen::VectorXd | u_lb, | ||
const Eigen::VectorXd | u_ub | ||
) |
check that control bounds are respected
References n.
void assertStateBounds | ( | const ct::core::StateVectorArray< state_dim > & | x, |
const Eigen::VectorXi | sparsity, | ||
const Eigen::VectorXd | x_lb, | ||
const Eigen::VectorXd | x_ub | ||
) |
check that state bounds are respected
References n.
void boxConstraintsTest | ( | ct::core::ControlVector< control_dim > | u0, |
ct::core::StateVector< state_dim > | x0, | ||
ct::core::StateVector< state_dim > | xf, | ||
int | nb_u, | ||
Eigen::VectorXd | u_lb, | ||
Eigen::VectorXd | u_ub, | ||
Eigen::VectorXi | u_box_sparsity, | ||
int | nb_x, | ||
Eigen::VectorXd | x_lb, | ||
Eigen::VectorXd | x_ub, | ||
Eigen::VectorXi | x_box_sparsity | ||
) |
void generalConstraintsTest | ( | ct::core::ControlVector< control_dim > | u0, |
ct::core::StateVector< state_dim > | x0, | ||
ct::core::StateVector< state_dim > | xf, | ||
Eigen::VectorXd | d_lb, | ||
Eigen::VectorXd | d_ub, | ||
Eigen::MatrixXd | C, | ||
Eigen::MatrixXd | D | ||
) |
TEST | ( | ConstrainedLQOCSolverTest | , |
BoxConstrTest_small | |||
) |
References control_dim, state_dim, and x0.
TEST | ( | ConstrainedLQOCSolverTest | , |
BoxConstrTest_medium | |||
) |
References control_dim, state_dim, and x0.
TEST | ( | ConstrainedLQOCSolverTest | , |
GeneralConstrTest_small | |||
) |
References control_dim, state_dim, and x0.
TEST | ( | ConstrainedLQOCSolverTest | , |
GeneralConstrTest_medium | |||
) |
References control_dim, state_dim, and x0.
TEST | ( | ConstrainedLQOCSolverTest | , |
BoxConstraintUsingConstraintToolbox | |||
) |
bool verbose = false |
Referenced by boxConstraintsTest(), generalConstraintsTest(), and TEST().