Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef TOWR_TOWR_H_
00031 #define TOWR_TOWR_H_
00032
00033 #include <ifopt/problem.h>
00034
00035 #include <iostream>
00036
00037 #include <ifopt_ipopt/ipopt_adapter.h>
00038
00039 #include <towr/variables/spline_holder.h>
00040
00041 #include "robot_model.h"
00042 #include "height_map.h"
00043 #include "nlp_factory.h"
00044 #include "parameters.h"
00045 #include "nlp_factory.h"
00046
00047
00048 namespace towr {
00049
00063 class TOWR {
00064 public:
00065 using FeetPos = std::vector<Eigen::Vector3d>;
00066
00067 TOWR ()
00068 {
00069 using namespace std;
00070 cout << "\n";
00071 cout << "************************************************************\n";
00072 cout << " TOWR - Trajectory Optimizer for Walking Robots (v1.1.0)\n";
00073 cout << " \u00a9 Alexander W. Winkler\n";
00074 cout << " https://github.com/ethz-adrl/towr\n";
00075 cout << "************************************************************";
00076 cout << "\n\n";
00077 }
00078 virtual ~TOWR () = default;
00079
00086 void SetInitialState(const BaseState& base, const FeetPos& feet)
00087 {
00088 factory_.initial_base_ = base;
00089 factory_.initial_ee_W_ = feet;
00090 }
00091
00100 void SetParameters(const BaseState& final_base,
00101 const Parameters& params,
00102 const RobotModel& model,
00103 HeightMap::Ptr terrain)
00104 {
00105 factory_.final_base_ = final_base;
00106 factory_.params_ = params;
00107 factory_.model_ = model;
00108 factory_.terrain_ = terrain;
00109 }
00110
00117 void SolveNLP()
00118 {
00119 nlp_ = BuildNLP();
00120
00121 ifopt::IpoptAdapter::Solve(nlp_);
00122
00123
00124 nlp_.PrintCurrent();
00125 }
00126
00133 SplineHolder GetSolution() const
00134 {
00135 return factory_.spline_holder_;
00136 }
00137
00146 void SetSolution(int solver_iteration)
00147 {
00148 nlp_.SetOptVariables(solver_iteration);
00149 }
00150
00154 int GetIterationCount() const
00155 {
00156 return nlp_.GetIterationCount();
00157 }
00158
00159 private:
00166 ifopt::Problem nlp_;
00167
00168 NlpFactory factory_;
00169
00173 ifopt::Problem BuildNLP()
00174 {
00175 ifopt::Problem nlp;
00176
00177 for (auto c : factory_.GetVariableSets())
00178 nlp.AddVariableSet(c);
00179
00180 for (auto c : factory_.GetConstraints())
00181 nlp.AddConstraintSet(c);
00182
00183 for (auto c : factory_.GetCosts())
00184 nlp.AddCostSet(c);
00185
00186 return nlp;
00187 }
00188 };
00189
00190 }
00191
00192 #endif