Austin Schuh | 7400da0 | 2018-01-28 19:54:58 -0800 | [diff] [blame^] | 1 | /*! |
| 2 | * \example NLOC_boxConstrained.cpp |
| 3 | * |
| 4 | * This example shows how to use box constraints alongside NLOC and requires HPIPM to be installed |
| 5 | * The unconstrained Riccati backward-pass is replaced by a high-performance interior-point |
| 6 | * constrained linear-quadratic Optimal Control solver. |
| 7 | * |
| 8 | */ |
| 9 | #include <ct/optcon/optcon.h> |
| 10 | #include "exampleDir.h" |
| 11 | #include "plotResultsOscillator.h" |
| 12 | |
| 13 | using namespace ct::core; |
| 14 | using namespace ct::optcon; |
| 15 | |
| 16 | |
| 17 | int main(int argc, char **argv) |
| 18 | { |
| 19 | /*get the state and control input dimension of the oscillator. Since we're dealing with a simple oscillator, |
| 20 | the state and control dimensions will be state_dim = 2, and control_dim = 1. */ |
| 21 | const size_t state_dim = ct::core::SecondOrderSystem::STATE_DIM; |
| 22 | const size_t control_dim = ct::core::SecondOrderSystem::CONTROL_DIM; |
| 23 | |
| 24 | |
| 25 | /* STEP 1: set up the Nonlinear Optimal Control Problem |
| 26 | * First of all, we need to create instances of the system dynamics, the linearized system and the cost function. */ |
| 27 | |
| 28 | /* STEP 1-A: create a instance of the oscillator dynamics for the optimal control problem. |
| 29 | * Please also compare the documentation of SecondOrderSystem.h */ |
| 30 | double w_n = 0.1; |
| 31 | double zeta = 5.0; |
| 32 | std::shared_ptr<ct::core::ControlledSystem<state_dim, control_dim>> oscillatorDynamics( |
| 33 | new ct::core::SecondOrderSystem(w_n, zeta)); |
| 34 | |
| 35 | |
| 36 | /* STEP 1-B: Although the first order derivatives of the oscillator are easy to derive, let's illustrate the use of the System Linearizer, |
| 37 | * which performs numerical differentiation by the finite-difference method. The system linearizer simply takes the |
| 38 | * the system dynamics as argument. Alternatively, you could implement your own first-order derivatives by overloading the class LinearSystem.h */ |
| 39 | std::shared_ptr<ct::core::SystemLinearizer<state_dim, control_dim>> adLinearizer( |
| 40 | new ct::core::SystemLinearizer<state_dim, control_dim>(oscillatorDynamics)); |
| 41 | |
| 42 | |
| 43 | /* STEP 1-C: create a cost function. We have pre-specified the cost-function weights for this problem in "nlocCost.info". |
| 44 | * Here, we show how to create terms for intermediate and final cost and how to automatically load them from the configuration file. |
| 45 | * The verbose option allows to print information about the loaded terms on the terminal. */ |
| 46 | std::shared_ptr<ct::optcon::TermQuadratic<state_dim, control_dim>> intermediateCost( |
| 47 | new ct::optcon::TermQuadratic<state_dim, control_dim>()); |
| 48 | std::shared_ptr<ct::optcon::TermQuadratic<state_dim, control_dim>> finalCost( |
| 49 | new ct::optcon::TermQuadratic<state_dim, control_dim>()); |
| 50 | bool verbose = true; |
| 51 | intermediateCost->loadConfigFile(ct::optcon::exampleDir + "/nlocCost.info", "intermediateCost", verbose); |
| 52 | finalCost->loadConfigFile(ct::optcon::exampleDir + "/nlocCost.info", "finalCost", verbose); |
| 53 | |
| 54 | // Since we are using quadratic cost function terms in this example, the first and second order derivatives are immediately known and we |
| 55 | // define the cost function to be an "Analytical Cost Function". Let's create the corresponding object and add the previously loaded |
| 56 | // intermediate and final term. |
| 57 | std::shared_ptr<CostFunctionQuadratic<state_dim, control_dim>> costFunction( |
| 58 | new CostFunctionAnalytical<state_dim, control_dim>()); |
| 59 | costFunction->addIntermediateTerm(intermediateCost); |
| 60 | costFunction->addFinalTerm(finalCost); |
| 61 | |
| 62 | |
| 63 | /* STEP 1-D: set up the box constraints for the control input*/ |
| 64 | // input box constraint boundaries with sparsities in constraint toolbox format |
| 65 | Eigen::VectorXi sp_control(control_dim); |
| 66 | sp_control << 1; |
| 67 | Eigen::VectorXd u_lb(control_dim); |
| 68 | Eigen::VectorXd u_ub(control_dim); |
| 69 | u_lb.setConstant(-0.5); |
| 70 | u_ub = -u_lb; |
| 71 | |
| 72 | // constraint terms |
| 73 | std::shared_ptr<ControlInputConstraint<state_dim, control_dim>> controlConstraint( |
| 74 | new ControlInputConstraint<state_dim, control_dim>(u_lb, u_ub, sp_control)); |
| 75 | controlConstraint->setName("ControlInputConstraint"); |
| 76 | |
| 77 | // create constraint container |
| 78 | std::shared_ptr<ConstraintContainerAnalytical<state_dim, control_dim>> boxConstraints( |
| 79 | new ct::optcon::ConstraintContainerAnalytical<state_dim, control_dim>()); |
| 80 | |
| 81 | // add and initialize constraint terms |
| 82 | boxConstraints->addIntermediateConstraint(controlConstraint, verbose); |
| 83 | boxConstraints->initialize(); |
| 84 | |
| 85 | |
| 86 | /* STEP 1-E: initialization with initial state and desired time horizon */ |
| 87 | |
| 88 | StateVector<state_dim> x0; |
| 89 | x0.setRandom(); // in this example, we choose a random initial state x0 |
| 90 | |
| 91 | ct::core::Time timeHorizon = 3.0; // and a final time horizon in [sec] |
| 92 | |
| 93 | |
| 94 | // STEP 1-E: create and initialize an "optimal control problem" |
| 95 | OptConProblem<state_dim, control_dim> optConProblem( |
| 96 | timeHorizon, x0, oscillatorDynamics, costFunction, adLinearizer); |
| 97 | |
| 98 | // add the box constraints to the optimal control problem |
| 99 | optConProblem.setBoxConstraints(boxConstraints); |
| 100 | |
| 101 | /* STEP 2: set up a nonlinear optimal control solver. */ |
| 102 | |
| 103 | /* STEP 2-A: Create the settings. |
| 104 | * the type of solver, and most parameters, like number of shooting intervals, etc., |
| 105 | * can be chosen using the following settings struct. Let's use, the iterative |
| 106 | * linear quadratic regulator, iLQR, for this example. In the following, we |
| 107 | * modify only a few settings, for more detail, check out the NLOptConSettings class. */ |
| 108 | NLOptConSettings ilqr_settings; |
| 109 | ilqr_settings.dt = 0.01; // the control discretization in [sec] |
| 110 | ilqr_settings.integrator = ct::core::IntegrationType::EULERCT; |
| 111 | ilqr_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; |
| 112 | ilqr_settings.max_iterations = 10; |
| 113 | ilqr_settings.nThreads = 4; |
| 114 | ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; |
| 115 | ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; // solve LQ-problems using HPIPM |
| 116 | ilqr_settings.lqoc_solver_settings.num_lqoc_iterations = 10; // number of riccati sub-iterations |
| 117 | ilqr_settings.printSummary = true; |
| 118 | |
| 119 | |
| 120 | /* STEP 2-B: provide an initial guess */ |
| 121 | // calculate the number of time steps K |
| 122 | size_t K = ilqr_settings.computeK(timeHorizon); |
| 123 | |
| 124 | /* design trivial initial controller for iLQR. Note that in this simple example, |
| 125 | * we can simply use zero feedforward with zero feedback gains around the initial position. |
| 126 | * In more complex examples, a more elaborate initial guess may be required.*/ |
| 127 | FeedbackArray<state_dim, control_dim> u0_fb(K, FeedbackMatrix<state_dim, control_dim>::Zero()); |
| 128 | ControlVectorArray<control_dim> u0_ff(K, ControlVector<control_dim>::Zero()); |
| 129 | StateVectorArray<state_dim> x_ref_init(K + 1, x0); |
| 130 | NLOptConSolver<state_dim, control_dim>::Policy_t initController(x_ref_init, u0_ff, u0_fb, ilqr_settings.dt); |
| 131 | |
| 132 | |
| 133 | // STEP 2-C: create an NLOptConSolver instance |
| 134 | NLOptConSolver<state_dim, control_dim> iLQR(optConProblem, ilqr_settings); |
| 135 | |
| 136 | // set the initial guess |
| 137 | iLQR.setInitialGuess(initController); |
| 138 | |
| 139 | |
| 140 | // STEP 3: solve the optimal control problem |
| 141 | iLQR.solve(); |
| 142 | |
| 143 | |
| 144 | // STEP 4: retrieve the solution |
| 145 | ct::core::StateFeedbackController<state_dim, control_dim> solution = iLQR.getSolution(); |
| 146 | |
| 147 | // let's plot the output |
| 148 | plotResultsOscillator<state_dim, control_dim>(solution.x_ref(), solution.uff(), solution.time()); |
| 149 | } |