41 const std::string& _commonHeaderName
52 LOG(
LVL_DEBUG ) <<
"Solver: setup initialization... " << endl;
56 LOG(
LVL_DEBUG ) <<
"Solver: setup variables... " << endl;
60 LOG(
LVL_DEBUG ) <<
"Solver: setup multiplication routines... " << endl;
64 LOG(
LVL_DEBUG ) <<
"Solver: setup model simulation... " << endl;
68 LOG(
LVL_DEBUG ) <<
"Solver: setup objective evaluation... " << endl;
72 LOG(
LVL_DEBUG ) <<
"Solver: setup condensing... " << endl;
76 LOG(
LVL_DEBUG ) <<
"Solver: setup constraints... " << endl;
80 LOG(
LVL_DEBUG ) <<
"Solver: setup evaluation... " << endl;
84 LOG(
LVL_DEBUG ) <<
"Solver: setup auxiliary functions... " << endl;
169 code.
addStatement(
"/******************************************************************************/\n" );
173 code.
addStatement(
"/******************************************************************************/\n" );
293 return (
NX +
N * NU);
335 unsigned indexX =
getNY();
369 if (tmpFx.isGiven() ==
true)
371 if (variableObjS ==
YES)
390 if (variableObjS ==
YES)
424 if (tmpFu.isGiven() ==
true)
426 if (variableObjS ==
YES)
445 if (variableObjS ==
YES)
493 if (tmpFxEnd.isGiven() ==
true)
516 int hardcodeConstraintValues;
537 DVector lbBoundValues( numBounds );
538 DVector ubBoundValues( numBounds );
541 for(
unsigned el = 0; el <
NX; ++el)
548 for(
unsigned node = 0; node <
N; ++node)
549 for(
unsigned el = 0; el <
NU; ++el)
555 if (hardcodeConstraintValues ==
YES)
574 for (
unsigned blk = 0; blk <
N; ++blk)
616 if (hardcodeConstraintValues ==
true)
620 if ( numStateBounds )
622 DVector lbStateBoundValues( numStateBounds );
623 DVector ubStateBoundValues( numStateBounds );
624 for (
unsigned i = 0; i < numStateBounds; ++i)
630 lbTmp.
append( lbStateBoundValues );
631 ubTmp.
append( ubStateBoundValues );
659 if ( numStateBounds )
668 for(
unsigned row = 0;
row < numStateBounds; ++
row)
671 unsigned blk = conIdx /
NX;
680 unsigned blkRow = ((N - blk) * (N - 1 - blk) / 2 + (N - 1 -
col)) * NX + conIdx %
NX;
691 DMatrix vXBoundIndices(1, numStateBounds);
692 for (
unsigned i = 0; i < numStateBounds; ++i)
713 lCol.
addStatement( blkIdx == (N - blk) * (N - 1 - blk) / 2 + (N - 1 - col) );
714 lCol.
addStatement( blkRow == blkIdx * NX + conIdx % NX );
716 A.
getSubMatrix(row, row + 1, offset + col * NU, offset + (col + 1) * NU ) ==
E.
getRow( blkRow ) );
753 unsigned prepCacheSize =
758 int useSinglePrecision;
760 prepCacheSize = prepCacheSize * (useSinglePrecision ? 4 : 8);
761 LOG(
LVL_DEBUG ) <<
"---> Condensing prep. part, cache size: " << prepCacheSize <<
" bytes" << endl;
788 unsigned row,
col, prev, curr;
789 for (row = 1; row <
N; ++
row)
793 for(col = 0; col <
row; ++
col)
795 prev = row * (row - 1) / 2 + col;
796 curr = (row + 1) * row / 2 + col;
801 curr = (row + 1) * row / 2 + col;
821 lRow.addStatement( lCol );
822 lRow.addStatement( curr == (row + 1) * row / 2 + col );
831 LOG(
LVL_DEBUG ) <<
"---> Setup condensing: H11" << endl;
863 unsigned curr = (
N) * (N - 1) / 2 + (N - 1 -
col);
883 unsigned next = (N - (
row + 1)) * (N - 1 - (
row + 1)) / 2 + (N - 1 -
col);
914 colLoop << (curr == (
N) * (
N - 1) / 2 + (
N - 1 -
col));
930 rowLoop << (next == (
N - (row + 1)) * (
N - 1 - (row + 1)) / 2 + (
N - 1 -
col));
952 LOG(
LVL_DEBUG ) <<
"---> Copy H11 upper to lower triangular part" << endl;
970 lRow.addStatement( lCol );
977 LOG(
LVL_DEBUG ) <<
"---> Factorization of the condensed Hessian" << endl;
1058 for (
unsigned blk =
N - 1; blk > 0; --blk)
1075 unsigned row =
N - 1 - blk;
1084 unsigned blkE = (N - (row + 1)) * (N - 1 - (row + 1)) / 2 + (N - 1 -
col);
1085 cout <<
"blkE " << blkE << endl;
1104 unsigned blkE = (N - 0) * (N - 1 - 0) / 2 + (N - 1 -
col);
1109 for (
unsigned blk = N - 1; blk > 0; --blk)
1111 unsigned row = N - 1 - blk;
1143 unsigned blkE = (N - (row + 1)) * (N - 1 - (row + 1)) / 2 + (N - 1 -
col);
1153 unsigned blkE = (N - (row + 1)) * (N - 1 - (row + 1)) / 2 + (N - 1 -
col);
1167 colLoop << (blkE == (
N - 0) * (
N - 1 - 0) / 2 + (
N - 1 -
col));
1173 blkLoop << ( row ==
N - 1 - blk );
1197 colLoop2 << (blkE == (
N - (row + 1)) * (
N - 1 - (row + 1)) / 2 + (
N - 1 -
col));
1199 blkLoop << colLoop2;
1204 colLoop3 << (blkE == (
N - (row + 1)) * (
N - 1 - (row + 1)) / 2 + (
N - 1 -
col));
1206 blkLoop << colLoop3;
1229 LOG(
LVL_DEBUG ) <<
"Setup condensing: create Dx0, Dy and DyN" << endl;
1241 for(
unsigned blk = 0; blk <
N; ++blk)
1258 for(
unsigned blk = 0; blk <
N; blk++ )
1309 for (
unsigned i = 0; i <
N; ++i)
1318 for (
unsigned i = N - 1; 0 < i; --i)
1372 LOG(
LVL_DEBUG ) <<
"Setup condensing: create expand routine" << endl;
1413 bool boxConIsFinite =
false;
1419 for (
int i = dimBox - 1; i >= 0; --i)
1425 boxConIsFinite =
true;
1428 if (boxConIsFinite ==
false || i == 0)
1431 for (
unsigned j = 0; j < lbBox.
getDim(); ++j)
1444 x0.
setDoc( (std::string)
"Current state feedback vector." );
1503 ExportVariable R22, Dy1, RDy1, Q22, QDy1,
E1, U1, U2, H101, w11, w12, w13;
1558 H.
getSubMatrix(offset + iRow * NU, offset + (iRow + 1) * NU, offset + iCol * NU, offset + (iCol + 1) * NU) ==
1559 H.
getSubMatrix(offset + iCol * NU, offset + (iCol + 1) * NU, offset + iRow * NU, offset + (iRow + 1) * NU).
getTranspose()
1641 H.
getSubMatrix(iRow * NU, (iRow + 1) * NU, iCol * NU, (iCol + 1) * NU) ==
1663 H.
getSubMatrix(iRow * NU, (iRow + 1) * NU, iRow * NU, (iRow + 1) * NU) ==
1667 H.
getSubMatrix(iRow * NU, (iRow + 1) * NU, iRow * NU, (iRow + 1) * NU) += mRegH11
1738 H1.
getSubMatrix(iRow * NU, (iRow + 1) * NU, iCol * NU, (iCol + 1) * NU) == L1 * Gu1
1784 retSim.
setDoc(
"Status of the integration module. =0: OK, otherwise the error code.");
1799 tmp.
setDoc(
"Status code of the qpOASES QP solver." );
1805 feedback.
doc(
"Feedback/estimation step of the RTI scheme." );
1812 s << tmp.
getName() <<
" = " << solve.
getName() <<
"( );" << endl;
1829 getKKT.
doc(
"Get the KKT tolerance of the current iterate." );
1830 kkt.
setDoc(
"The KKT tolerance value." );
1875 std::string sourceFile, headerFile, solverDefine;
1881 sourceFile = folderName +
"/" + moduleName +
"_qpoases_interface.cpp";
1882 headerFile = folderName +
"/" + moduleName +
"_qpoases_interface.hpp";
1883 solverDefine =
"QPOASES_HEADER";
1888 sourceFile = folderName +
"/" + moduleName +
"_qpoases3_interface.c";
1889 headerFile = folderName +
"/" + moduleName +
"_qpoases3_interface.h";
1890 solverDefine =
"QPOASES3_HEADER";
1896 "For condensed solution only qpOASES and qpOASES3 QP solver are supported");
1899 int useSinglePrecision;
1908 int maxNumQPiterations;
1911 int externalCholesky;
1918 if ( qpInterface == 0 )
1950 if ( qpInterface != 0 )
1958 int sparseQPsolution;
uint getNumPoints() const
unsigned getNumQPvars() const
ExportFunction move_GxT_T3
#define LOG(level)
Just define a handy macro for getting the logger.
Lowest level, the debug level.
ExportFunction expansionStep
virtual returnValue getCode(ExportStatementBlock &code)
std::string getFullName() const
const ExportFunction & getCholeskyFunction() const
virtual returnValue setup()
ExportFunction shiftStates
ExportCholeskySolver cholSolver
virtual returnValue setupMultiplicationRoutines()
ExportFunction macBTW1_R1
ExportVariable & setup(const std::string &_name, uint _nRows=1, uint _nCols=1, ExportType _type=REAL, ExportStruct _dataStruct=ACADO_LOCAL, bool _callItByValue=false, const std::string &_prefix=std::string())
DVector getLowerBounds(uint pointIdx) const
bool performsSingleShooting() const
Allows to pass back messages to the calling function.
virtual returnValue setupEvaluation()
ExportFunction zeroBlockH10
virtual uint getDim() const
ExportVariable getRow(const ExportIndex &idx) const
ExportFunction evaluateObjective
virtual returnValue setupCondensing()
virtual returnValue configure(const std::string &_prefix, const std::string &_solverDefine, const int nvmax, const int ncmax, const int nwsrmax, const std::string &_printLevel, bool _useSinglePrecision, const std::string &_commonHeader, const std::string &_namespace, const std::string &_primalSolution, const std::string &_dualSolution, const std::string &_sigma, bool _hotstartQP, bool _externalCholesky, const std::string &_qpH, const std::string &_qpR, const std::string &_qpg, const std::string &_qpA, const std::string &_qplb, const std::string &_qpub, const std::string &_qplbA, const std::string &_qpubA)
std::vector< unsigned > xBoundsIdxRev
ExportFunction mul_T2_A_L
ExportVariable objEvFxEnd
bool performFullCondensing() const
Allows to export code of a for-loop.
string toString(T const &value)
#define CLOSE_NAMESPACE_ACADO
DVector getUpperBounds(uint pointIdx) const
Defines a scalar-valued index variable to be used for exporting code.
ExportVariable getSubMatrix(const ExportIndex &rowIdx1, const ExportIndex &rowIdx2, const ExportIndex &colIdx1, const ExportIndex &colIdx2) const
ExportFunction mult_H_W2T_W3
virtual returnValue setupVariables()
Base class for export of NLP/OCP solvers.
ExportAcadoFunction evaluateStageCost
A class for generating the glue code for interfacing qpOASES.
ExportVariable getRows(const ExportIndex &idx1, const ExportIndex &idx2) const
ExportFunction macATw1QDy
virtual returnValue getDataDeclarations(ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
ExportAcadoFunction evaluateTerminalCost
bool initialStateFixed() const
ExportFunction & setup(const std::string &_name="defaultFunctionName", const ExportArgument &_argument1=emptyConstExportArgument, const ExportArgument &_argument2=emptyConstExportArgument, const ExportArgument &_argument3=emptyConstExportArgument, const ExportArgument &_argument4=emptyConstExportArgument, const ExportArgument &_argument5=emptyConstExportArgument, const ExportArgument &_argument6=emptyConstExportArgument, const ExportArgument &_argument7=emptyConstExportArgument, const ExportArgument &_argument8=emptyConstExportArgument, const ExportArgument &_argument9=emptyConstExportArgument)
virtual returnValue setDoc(const std::string &_doc)
virtual returnValue setupInitialization()
std::string commonHeaderName
ExportFunction mac_W3_G_W1T_G
ExportFunction modelSimulation
virtual ExportFunction & doc(const std::string &_doc)
ExportFunction zeroBlockH00
ExportFunction mac_H_W2T_W3_R
virtual returnValue setupConstraintsEvaluation(void)
ExportFunction mac_W1_T1_E_F
ExportFunction getObjective
ExportFunction mac_R_BT_F_D
std::vector< unsigned > xBoundsIdx
ExportFunction condenseFdb
returnValue init(unsigned _dimA, unsigned _numColsB, const std::string &_id)
ExportVariable objValueIn
ExportFunction initializeNodes
double levenbergMarquardt
bool isGiven(const ExportIndex &rowIdx, const ExportIndex &colIdx) const
virtual returnValue exportCode()
ExportVariable getTranspose() const
virtual returnValue setupSimulation(void)
std::vector< std::shared_ptr< ExportAcadoFunction > > evaluatePointConstraints
Encapsulates all user interaction for setting options, logging data and plotting results.
virtual returnValue getDataDeclarations(ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
Allows to export code of an arbitrary function.
ExportFunction shiftControls
returnValue addStatement(const ExportStatement &_statement)
std::string getName() const
ExportFunction setBlockH11
ExportFunction mult_L_E_U
returnValue addLinebreak(uint num=1)
virtual unsigned getNumStateBounds() const
ExportAcadoFunction evaluatePathConstraints
virtual returnValue setup()
ExportFunction mac_R_T2_B_D
GenericVector & append(const GenericVector &_arg)
ExportFunction zeroBlockH11
ExportFunction & setReturnValue(const ExportVariable &_functionReturnValue, bool _returnAsPointer=false)
virtual ExportFunction & acquire(ExportIndex &obj)
ExportFunction & addVariable(const ExportVariable &_var)
ExportFunction mult_BT_T1_T2
BooleanType acadoIsFinite(double x, double TOL)
ExportFunction setObjQ1Q2
const ExportFunction & getSolveFunction() const
virtual returnValue setupQPInterface()
ExportVariable objSEndTerm
returnValue addDeclaration(const ExportVariable &_data, ExportStruct _dataStruct=ACADO_ANY)
returnValue setupAuxiliaryFunctions()
ExportArgument getAddress(const ExportIndex &_rowIdx, const ExportIndex &_colIdx=emptyConstExportIndex) const
virtual ExportFunction & release(const ExportIndex &obj)
unsigned getNumComplexConstraints(void)
Expression next(const Expression &arg)
std::string getName() const
#define BEGIN_NAMESPACE_ACADO
BooleanType isFinite(const T &_value)
virtual returnValue getFunctionDeclarations(ExportStatementBlock &declarations) const
const std::string get(const ExportIndex &rowIdx, const ExportIndex &colIdx) const
returnValue addFunction(const ExportFunction &_function)
CondensedHessianCholeskyDecomposition
A class for generating the glue code for interfacing qpOASES.
double getLowerBound(uint pointIdx, uint valueIdx) const
virtual returnValue getCode(ExportStatementBlock &code)
ExportVariable getCols(const ExportIndex &idx1, const ExportIndex &idx2) const
ExportVariable makeRowVector() const
Allows to export code for a block of statements.
ExportFunction initialize
virtual returnValue setupObjectiveEvaluation(void)
ExportFunction condensePrep
ExportVariable objValueOut
ExportFunction setObjQN1QN2
ExportFunction mult_FT_A_L
ExportVariable getCol(const ExportIndex &idx) const
ExportFunction & addIndex(const ExportIndex &_index)
ExportGaussNewtonCn2Factorization(UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
double getUpperBound(uint pointIdx, uint valueIdx) const
ExportFunction macQSbarW2
#define ACADOERROR(retval)
ExportFunction preparation
ExportVariable makeColVector() const
Defines a matrix-valued variable to be used for exporting code.
ExportFunction setObjR1R2
#define ACADOERRORTEXT(retval, text)
returnValue addFunctionCall(const std::string &_fName, const ExportArgument &_argument1=emptyConstExportArgument, const ExportArgument &_argument2=emptyConstExportArgument, const ExportArgument &_argument3=emptyConstExportArgument, const ExportArgument &_argument4=emptyConstExportArgument, const ExportArgument &_argument5=emptyConstExportArgument, const ExportArgument &_argument6=emptyConstExportArgument, const ExportArgument &_argument7=emptyConstExportArgument, const ExportArgument &_argument8=emptyConstExportArgument, const ExportArgument &_argument9=emptyConstExportArgument)