nlp_solver.cpp
Go to the documentation of this file.
00001 /*
00002  *    This file is part of ACADO Toolkit.
00003  *
00004  *    ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
00005  *    Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
00006  *    Milan Vukov, Rien Quirynen, KU Leuven.
00007  *    Developed within the Optimization in Engineering Center (OPTEC)
00008  *    under supervision of Moritz Diehl. All rights reserved.
00009  *
00010  *    ACADO Toolkit is free software; you can redistribute it and/or
00011  *    modify it under the terms of the GNU Lesser General Public
00012  *    License as published by the Free Software Foundation; either
00013  *    version 3 of the License, or (at your option) any later version.
00014  *
00015  *    ACADO Toolkit is distributed in the hope that it will be useful,
00016  *    but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018  *    Lesser General Public License for more details.
00019  *
00020  *    You should have received a copy of the GNU Lesser General Public
00021  *    License along with ACADO Toolkit; if not, write to the Free Software
00022  *    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00023  *
00024  */
00025 
00026 
00034 #include <acado/nlp_solver/nlp_solver.hpp>
00035 
00036 
00037 
00038 BEGIN_NAMESPACE_ACADO
00039 
00040 
00041 
00042 //
00043 // PUBLIC MEMBER FUNCTIONS:
00044 //
00045 
00046 NLPsolver::NLPsolver( UserInteraction* _userInteraction ) : AlgorithmicBase( _userInteraction )
00047 {
00048         // setup options and loggings for stand-alone instances
00049         if ( _userInteraction == 0 )
00050         {
00051                 setupOptions( );
00052                 setupLogging( );
00053         }
00054         
00055     numberOfSteps = 0;
00056 }
00057 
00058 
00059 NLPsolver::NLPsolver( const NLPsolver& rhs ) : AlgorithmicBase( rhs )
00060 {
00061     numberOfSteps = rhs.numberOfSteps;
00062 }
00063 
00064 
00065 NLPsolver::~NLPsolver( ){
00066 
00067 }
00068 
00069 
00070 NLPsolver& NLPsolver::operator=( const NLPsolver& rhs )
00071 {
00072     if ( this != &rhs )
00073     {
00074                 AlgorithmicBase::operator=( rhs );
00075 
00076                 numberOfSteps = rhs.numberOfSteps;
00077     }
00078 
00079     return *this;
00080 }
00081 
00082 returnValue NLPsolver::solve(   const DVector &x0_, const DVector &p_
00083                                                                 ){
00084     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00085 }
00086 
00087 
00088 
00089 returnValue NLPsolver::feedbackStep( const DVector &x0_, const DVector &p_ )
00090 {
00091     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00092 }
00093 
00094 
00095 returnValue NLPsolver::performCurrentStep( )
00096 {
00097     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00098 }
00099 
00100 
00101 returnValue NLPsolver::prepareNextStep( )
00102 {
00103     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00104 }
00105 
00106 
00107 returnValue NLPsolver::step( const DVector &x0_, const DVector &p_ )
00108 {
00109     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00110 }
00111 
00112 
00113 
00114 returnValue NLPsolver::shiftVariables(  double timeShift,
00115                                                             DVector  lastX,
00116                                                             DVector  lastXA,
00117                                                                 DVector  lastP,
00118                                                                 DVector  lastU,
00119                                                                 DVector  lastW  )
00120 {
00121     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00122 }
00123 
00124 
00125 returnValue NLPsolver::setReference( const VariablesGrid &ref ){
00126 
00127     return ACADOERROR(RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE);
00128 }
00129 
00130 
00131 returnValue NLPsolver::getDifferentialStates( VariablesGrid &xd_ ) const{
00132 
00133     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00134 }
00135 
00136 
00137 returnValue NLPsolver::getAlgebraicStates( VariablesGrid &xa_ ) const{
00138 
00139     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00140 }
00141 
00142 
00143 returnValue NLPsolver::getParameters( VariablesGrid &p_  ) const{
00144 
00145     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00146 }
00147 
00148 returnValue NLPsolver::getParameters( DVector &p_  ) const{
00149 
00150     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00151 }
00152 
00153 
00154 returnValue NLPsolver::getControls( VariablesGrid &u_  ) const{
00155 
00156     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00157 }
00158 
00159 
00160 returnValue NLPsolver::getFirstControl( DVector& u_  ) const{
00161 
00162     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00163 }
00164 
00165 
00166 returnValue NLPsolver::getDisturbances( VariablesGrid &w_  ) const{
00167 
00168     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00169 }
00170 
00171 
00172 double NLPsolver::getObjectiveValue( ) const{
00173 
00174     return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00175 }
00176 
00177 
00178 returnValue NLPsolver::getSensitivitiesX(       BlockMatrix& _sens
00179                                                                                         ) const
00180 {
00181         return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00182 }
00183 
00184 
00185 returnValue NLPsolver::getSensitivitiesXA(      BlockMatrix& _sens
00186                                                                                         ) const
00187 {
00188         return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00189 }
00190 
00191 returnValue NLPsolver::getSensitivitiesP(       BlockMatrix& _sens
00192                                                                                         ) const
00193 {
00194         return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00195 }
00196 
00197 
00198 returnValue NLPsolver::getSensitivitiesU(       BlockMatrix& _sens
00199                                                                                         ) const
00200 {
00201         return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00202 }
00203 
00204 
00205 returnValue NLPsolver::getSensitivitiesW(       BlockMatrix& _sens
00206                                                                                         ) const
00207 {
00208         return ACADOERROR(RET_NOT_IMPLEMENTED_YET);
00209 }
00210 
00211 
00212 
00213 //
00214 // PROTECTED MEMBER FUNCTIONS:
00215 //
00216 
00217 returnValue NLPsolver::setupOptions( )
00218 {
00219         addOption( MAX_NUM_ITERATIONS          , defaultMaxNumIterations        );
00220         addOption( KKT_TOLERANCE               , defaultKKTtolerance            );
00221         addOption( KKT_TOLERANCE_SAFEGUARD     , defaultKKTtoleranceSafeguard   );
00222         addOption( LEVENBERG_MARQUARDT         , defaultLevenbergMarguardt      );
00223         addOption( HESSIAN_PROJECTION_FACTOR   , defaultHessianProjectionFactor );
00224         addOption( PRINTLEVEL                  , defaultPrintlevel              );
00225         addOption( PRINT_COPYRIGHT             , defaultPrintCopyright          );
00226         addOption( HESSIAN_APPROXIMATION       , defaultHessianApproximation    );
00227         addOption( DYNAMIC_HESSIAN_APPROXIMATION, defaultDynamicHessianApproximation );
00228         addOption( DYNAMIC_SENSITIVITY         , defaultDynamicSensitivity      );
00229         addOption( OBJECTIVE_SENSITIVITY       , defaultObjectiveSensitivity    );
00230         addOption( CONSTRAINT_SENSITIVITY      , defaultConstraintSensitivity   );
00231         addOption( DISCRETIZATION_TYPE         , defaultDiscretizationType      );
00232         addOption( LINESEARCH_TOLERANCE        , defaultLinesearchTolerance     );
00233         addOption( MIN_LINESEARCH_PARAMETER    , defaultMinLinesearchParameter  );
00234         addOption( MAX_NUM_QP_ITERATIONS       , defaultMaxNumQPiterations      );
00235         addOption( HOTSTART_QP                 , defaultHotstartQP              );
00236         addOption( INFEASIBLE_QP_RELAXATION    , defaultInfeasibleQPrelaxation  );
00237         addOption( INFEASIBLE_QP_HANDLING      , defaultInfeasibleQPhandling    );
00238         addOption( USE_REALTIME_ITERATIONS     , defaultUseRealtimeIterations   );
00239         addOption( TERMINATE_AT_CONVERGENCE    , defaultTerminateAtConvergence  );
00240         addOption( SPARSE_QP_SOLUTION          , defaultSparseQPsolution        );
00241         addOption( GLOBALIZATION_STRATEGY      , defaultGlobalizationStrategy   );
00242         addOption( PRINT_SCP_METHOD_PROFILE    , defaultprintSCPmethodProfile   );
00243 
00244         return SUCCESSFUL_RETURN;
00245 }
00246 
00247 
00248 returnValue NLPsolver::setupLogging( )
00249 {
00250 //      LogRecord tmp( LOG_AT_EACH_ITERATION,stdout,PS_DEFAULT,BT_FALSE );
00251 
00252 //      addLogRecord( tmp );
00253 
00254         return SUCCESSFUL_RETURN;
00255 }
00256 
00257 
00258 CLOSE_NAMESPACE_ACADO
00259 
00260 // end of file.


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 11:59:22