42 const std::string& _commonHeaderName
48 LOG(
LVL_DEBUG ) <<
"Solver: setup initialization... " << endl;
52 LOG(
LVL_DEBUG ) <<
"Solver: setup variables... " << endl;
56 LOG(
LVL_DEBUG ) <<
"Solver: setup multiplication routines... " << endl;
60 LOG(
LVL_DEBUG ) <<
"Solver: setup model simulation... " << endl;
64 LOG(
LVL_DEBUG ) <<
"Solver: setup arrival cost update... " << 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;
171 code.
addStatement(
"/******************************************************************************/\n" );
175 code.
addStatement(
"/******************************************************************************/\n" );
253 if (useArrivalCost ==
YES)
270 return (
NX +
N * NU);
291 "Mixed control-state terms in the objective function are not supported at the moment.");
316 unsigned indexX =
getNY();
350 if (tmpFx.isGiven() ==
true)
352 if (variableObjS ==
YES)
371 if (variableObjS ==
YES)
403 if (tmpFu.isGiven() ==
true)
405 if (variableObjS ==
YES)
424 if (variableObjS ==
YES)
472 if (tmpFxEnd.isGiven() ==
true)
495 int hardcodeConstraintValues;
508 unsigned numPointCon =
dimPocH;
516 DVector lbBoundValues( numBounds );
517 DVector ubBoundValues( numBounds );
520 for(
unsigned el = 0; el <
NX; ++el)
526 for(
unsigned node = 0; node <
N; ++node)
527 for(
unsigned el = 0; el <
NU; ++el)
533 if (hardcodeConstraintValues ==
YES || !(
isFinite( lbBoundValues ) ||
isFinite( ubBoundValues )))
593 if ( numStateBounds )
595 DVector lbStateBoundValues( numStateBounds );
596 DVector ubStateBoundValues( numStateBounds );
597 for (
unsigned i = 0; i < numStateBounds; ++i)
603 lbTmp.
append( lbStateBoundValues );
604 ubTmp.
append( ubStateBoundValues );
613 if (hardcodeConstraintValues ==
true)
636 if ( numStateBounds )
645 for(
unsigned row = 0;
row < numStateBounds; ++
row)
652 unsigned blk = conIdx / NX + 1;
655 unsigned blkRow = (blk * (blk - 1) / 2 +
col) * NX + conIdx %
NX;
666 DMatrix vXBoundIndices(1, numStateBounds);
667 for (
unsigned i = 0; i < numStateBounds; ++i)
687 lCol.
addStatement( blkRow == (blk * (blk - 1) / 2 + col ) * NX + conIdx % NX );
689 A.
getSubMatrix(row, row + 1, offset + col * NU, offset + (col + 1) * NU ) ==
E.
getRow( blkRow ) );
699 for(
unsigned run1 = 0; run1 < numStateBounds; ++run1)
742 unsigned rowOffset = numStateBounds;
768 getCols(runPac * dimPacH * NX, (runPac + 1) * dimPacH * NX)
772 derOffset = derOffset + dimPacH *
NX;
778 getCols(runPac * dimPacH * NU, (runPac + 1) * dimPacH * NU)
833 for (
unsigned row = 0;
row < N - 1; ++
row)
864 rowOffset + (iRow + 1) * dimPacH,
865 colOffset + iCol * NU,
866 colOffset + (iCol + 1) * NU)
871 for (
unsigned row = 0;
row < N - 1; ++
row)
875 unsigned blk = (
row + 1) *
row / 2 +
col;
876 unsigned row2 =
row + 1;
908 eLoopJ.
addStatement( blk == (row + 1) * row / 2 + col );
944 for (
unsigned i = 0; i <
N; ++i)
949 rowOffset + i * dimPacH,
950 rowOffset + (i + 1) * dimPacH,
952 colOffset + (i + 1) * NU)
958 rowOffset + i * dimPacH,
959 rowOffset + (i + 1) * dimPacH,
961 colOffset + (i + 1) * NU)
963 i * dimPacH,(i + 1) * dimPacH, 0, NU)
1001 for (
unsigned i = 0; i < N - 1; ++i)
1046 for (
unsigned i = 0, intRowOffset = 0; i < N + 1; ++i)
1079 (intRowOffset + dim) * NX)
1087 (intRowOffset + dim) * NU)
1089 dim + dim * NX + dim * NU));
1093 intRowOffset += dim;
1099 for (
unsigned row = 0, intRowOffset = 0;
row < N + 1; ++
row)
1105 string(
"Evaluating multiplications of constraint functions on node: #" ) +
toString(
row ) );
1141 A.
getSubMatrix(rowOffset + intRowOffset, rowOffset + intRowOffset + dim, 0, NX) ==
1155 A.
getSubMatrix(rowOffset + intRowOffset, rowOffset + intRowOffset + dim,
1156 colOffset + iCol * NU, colOffset + (iCol + 1) * NU) ==
1179 A.
getSubMatrix(rowOffset + intRowOffset, rowOffset + intRowOffset + dim,
1180 colOffset +
row * NU, colOffset + (
row + 1) * NU) ==
1186 intRowOffset += dim;
1240 LOG(
LVL_DEBUG ) <<
"Setup condensing: create C & E matrices" << endl;
1247 unsigned row,
col, prev, curr;
1248 for (row = 1; row <
N; ++
row)
1258 for(col = 0; col <
row; ++
col)
1260 prev = row * (row - 1) / 2 + col;
1261 curr = (row + 1) * row / 2 + col;
1267 curr = (row + 1) * row / 2 + col;
1292 eLoopJ.
addStatement( prev == row * (row - 1) / 2 + col );
1293 eLoopJ.
addStatement( curr == (row + 1) * row / 2 + col );
1297 eLoopI.
addStatement( curr == (row + 1) * row / 2 + col );
1312 LOG(
LVL_DEBUG ) <<
"Setup condensing: multiply with Q1" << endl;
1316 for (
unsigned i = 0; i <
N - 1; ++i)
1331 for (
unsigned i = 0; i <
N; ++i)
1332 for (
unsigned j = 0; j <= i; ++j)
1334 unsigned k = (i + 1) * i / 2 + j;
1397 LOG(
LVL_DEBUG ) <<
"Setup condensing: create H00, H10 & H11" << endl;
1408 for (
unsigned i = 0; i <
N; ++i)
1438 for (
unsigned i = 0; i <
N; ++i)
1442 for (
unsigned j = i; j <
N; ++j)
1444 unsigned k = (j + 1) * j / 2 + i;
1494 for (row = 0; row <
N; ++
row)
1503 for(
unsigned blk = col; blk <
N; ++blk)
1505 unsigned indl = (blk + 1) * blk / 2 + row;
1506 unsigned indr = (blk + 1) * blk / 2 + col;
1515 for(col = row + 1; col <
N; ++
col)
1521 for(
unsigned blk = col; blk <
N; ++blk)
1523 unsigned indl = (blk + 1) * blk / 2 + row;
1524 unsigned indr = (blk + 1) * blk / 2 + col;
1552 eLoopK.
addStatement( indl == (blk + 1) * blk / 2 + row );
1553 eLoopK.
addStatement( indr == (blk + 1) * blk / 2 + col );
1560 eLoopK2.
addStatement( indl == (blk + 1) * blk / 2 + row );
1561 eLoopK2.
addStatement( indr == (blk + 1) * blk / 2 + col );
1572 LOG(
LVL_DEBUG ) <<
"---> Copy H11 lower part" << endl;
1579 for (
unsigned ii = 0; ii <
N; ++ii)
1580 for(
unsigned jj = 0; jj < ii; ++jj)
1615 int externalCholesky;
1640 LOG(
LVL_DEBUG ) <<
"Setup condensing: compute Qd" << endl;
1646 for(
unsigned i = 0; i <
N - 1; ++i)
1662 LOG(
LVL_DEBUG ) <<
"Setup condensing: create Dx0, Dy and DyN" << endl;
1675 for(
unsigned run1 = 0; run1 <
N; ++run1)
1692 for(
unsigned run1 = 0; run1 <
N; run1++ )
1709 LOG(
LVL_DEBUG ) <<
"Setup condensing: QDy.getRows(NX, (N + 1) * NX) += Qd" << endl;
1738 for (
unsigned i = 0; i <
N; ++i)
1739 for (
unsigned j = i; j <
N; ++j)
1741 unsigned k = (j + 1) * j / 2 + i;
1795 for (
unsigned i = 0; i <
N; ++i)
1805 for (
unsigned i = 0; i <
N; ++i)
1829 for (
unsigned i = 0; i <
N; ++i)
1830 for (
unsigned j = i; j <
N; ++j)
1832 unsigned k = (j + 1) * j / 2 + i;
1860 for (
unsigned i = 0; i <
N; ++i)
1873 LOG(
LVL_DEBUG ) <<
"Setup condensing: create expand routine" << endl;
1917 for (
unsigned i = 0; i <
N; ++i)
1918 for (
unsigned j = 0; j <= i; ++j)
1920 unsigned k = (i + 1) * i / 2 + j;
1962 "Calculation of covariance matrix works for partial condensing only atm.");
1964 LOG(
LVL_DEBUG ) <<
"Setup condensing: covariance matrix calculation" << endl;
1971 sigmaN.
setDoc(
"Covariance matrix of the last state estimate.");
1983 unsigned blk = (N - 1 + 1) * (N - 1) / 2;
1986 E.
getSubMatrix(blk * NX + cIndex * NX, blk * NX + NX + cIndex * NX, 0, NU)
2012 bool boxConIsFinite =
false;
2022 boxConIsFinite =
true;
2025 if (boxConIsFinite ==
false || i == 0)
2028 for (
unsigned j = 0; j < lbBox.
getDim(); ++j)
2040 x0.
setDoc( (std::string)
"Current state feedback vector." );
2160 H.
getSubMatrix(offset + iRow * NU, offset + (iRow + 1) * NU, offset + iCol * NU, offset + (iCol + 1) * NU) ==
2161 H.
getSubMatrix(offset + iCol * NU, offset + (iCol + 1) * NU, offset + iRow * NU, offset + (iRow + 1) * NU).
getTranspose()
2250 retSim.
setDoc(
"Status of the integration module. =0: OK, otherwise the error code.");
2265 tmp.
setDoc(
"Status code of the qpOASES QP solver." );
2271 feedback.
doc(
"Feedback/estimation step of the RTI scheme." );
2298 getKKT.
doc(
"Get the KKT tolerance of the current iterate." );
2299 kkt.
setDoc(
"The KKT tolerance value." );
2344 std::string sourceFile, headerFile, solverDefine;
2350 sourceFile = folderName +
"/" + moduleName +
"_qpoases_interface.cpp";
2351 headerFile = folderName +
"/" + moduleName +
"_qpoases_interface.hpp";
2352 solverDefine =
"QPOASES_HEADER";
2357 sourceFile = folderName +
"/" + moduleName +
"_qpoases3_interface.c";
2358 headerFile = folderName +
"/" + moduleName +
"_qpoases3_interface.h";
2359 solverDefine =
"QPOASES3_HEADER";
2365 "For condensed solution only qpOASES and qpOASES3 QP solver are supported");
2368 int useSinglePrecision;
2377 int maxNumQPiterations;
2380 int externalCholesky;
2387 if ( qpInterface == 0 )
2418 if ( qpInterface != 0 )
2426 int sparseQPsolution;
uint getNumPoints() const
#define LOG(level)
Just define a handy macro for getting the logger.
Lowest level, the debug level.
virtual returnValue setupObjectiveEvaluation(void)
virtual returnValue getCode(ExportStatementBlock &code)
ExportFunction condensePrep
std::string getFullName() const
const ExportFunction & getCholeskyFunction() const
ExportVariable conValueOut
ExportFunction zeroBlockH10
ExportCholeskySolver cholSolver
virtual returnValue setup()
const DMatrix & getGivenMatrix() const
ExportFunction shiftStates
virtual returnValue setupEvaluation()
ExportFunction setBlockH11
ExportFunction setBlockH11_R1
returnValue setupArrivalCostCalculation()
ExportFunction calculateCovariance
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())
virtual returnValue setupQPInterface()
DVector getLowerBounds(uint pointIdx) const
bool performsSingleShooting() const
Allows to pass back messages to the calling function.
ExportVariable conValueIn
virtual uint getDim() const
ExportVariable getRow(const ExportIndex &idx) const
returnValue addComment(const std::string &_comment)
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)
ExportVariable objEvFxEnd
virtual returnValue setupConstraintsEvaluation(void)
ExportFunction zeroBlockH00
Allows to export code of a for-loop.
ExportFunction condenseFdb
string toString(T const &value)
ExportFunction evaluateObjective
#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
Base class for export of NLP/OCP solvers.
ExportAcadoFunction evaluateStageCost
ExportGaussNewtonCondensed(UserInteraction *_userInteraction=0, const std::string &_commonHeaderName="")
A class for generating the glue code for interfacing qpOASES.
ExportVariable getRows(const ExportIndex &idx1, const ExportIndex &idx2) const
virtual returnValue getCode(ExportStatementBlock &code)
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 updateArrivalCost
ExportFunction modelSimulation
virtual ExportFunction & doc(const std::string &_doc)
virtual returnValue setupVariables()
ExportCholeskyDecomposition cholSAC
ExportFunction getObjective
virtual returnValue setupCondensing()
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)
virtual returnValue getDataDeclarations(ExportStatementBlock &declarations, ExportStruct dataStruct=ACADO_ANY) const
virtual returnValue setup()
std::vector< std::shared_ptr< ExportAcadoFunction > > evaluatePointConstraints
Encapsulates all user interaction for setting options, logging data and plotting results.
Allows to export code of an arbitrary function.
ExportFunction shiftControls
returnValue addStatement(const ExportStatement &_statement)
std::string getName() const
ExportFunction setObjQN1QN2
virtual returnValue getCode(ExportStatementBlock &code)
virtual returnValue setupMultiplicationRoutines()
ExportFunction zeroBlockH11
returnValue addLinebreak(uint num=1)
ExportAcadoFunction evaluatePathConstraints
GenericVector & append(const GenericVector &_arg)
#define ACADOWARNINGTEXT(retval, text)
ExportFunction & setReturnValue(const ExportVariable &_functionReturnValue, bool _returnAsPointer=false)
virtual ExportFunction & acquire(ExportIndex &obj)
ExportFunction & addVariable(const ExportVariable &_var)
BooleanType acadoIsFinite(double x, double TOL)
ExportHouseholderQR acSolver
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)
ExportFunction preparation
std::string getName() const
#define BEGIN_NAMESPACE_ACADO
std::vector< unsigned > xBoundsIdx
BooleanType isFinite(const T &_value)
virtual returnValue getCode(ExportStatementBlock &code)
const std::string get(const ExportIndex &rowIdx, const ExportIndex &colIdx) const
returnValue addFunction(const ExportFunction &_function)
bool performFullCondensing() const
CondensedHessianCholeskyDecomposition
ExportFunction setObjR1R2
virtual unsigned getNumStateBounds() const
A class for generating the glue code for interfacing qpOASES.
unsigned getNumQPvars() const
double getLowerBound(uint pointIdx, uint valueIdx) const
ExportCholeskyDecomposition cholObjS
virtual returnValue getFunctionDeclarations(ExportStatementBlock &declarations) const
ExportVariable getCols(const ExportIndex &idx1, const ExportIndex &idx2) const
ExportVariable makeRowVector() const
Allows to export code for a block of statements.
ExportFunction initialize
ExportFunction setObjQ1Q2
ExportVariable objValueOut
ExportVariable getCol(const ExportIndex &idx) const
ExportFunction & addIndex(const ExportIndex &_index)
double getUpperBound(uint pointIdx, uint valueIdx) const
ExportVariable makeColVector() const
Defines a matrix-valued variable to be used for exporting code.
#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)