Public Member Functions | Protected Member Functions | Protected Attributes

Implements different sequential convex programming methods for solving NLPs. More...

#include <scp_method.hpp>

Inheritance diagram for SCPmethod:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual NLPsolverclone () const
virtual returnValue feedbackStep (const DVector &x0_, const DVector &p_=emptyConstVector)
virtual returnValue getVarianceCovariance (DMatrix &var)
virtual returnValue init (VariablesGrid *x_init, VariablesGrid *xa_init, VariablesGrid *p_init, VariablesGrid *u_init, VariablesGrid *w_init)
SCPmethodoperator= (const SCPmethod &rhs)
virtual returnValue performCurrentStep ()
virtual returnValue prepareNextStep ()
virtual returnValue printRuntimeProfile () const
 SCPmethod ()
 SCPmethod (UserInteraction *_userInteraction, const Objective *objective_, const DynamicDiscretization *dynamic_discretization_, const Constraint *constraint_, BooleanType _isCP=BT_FALSE)
 SCPmethod (const SCPmethod &rhs)
virtual returnValue setReference (const VariablesGrid &ref)
virtual returnValue shiftVariables (double timeShift=-1.0, DVector lastX=emptyVector, DVector lastXA=emptyVector, DVector lastP=emptyVector, DVector lastU=emptyVector, DVector lastW=emptyVector)
virtual returnValue solve (const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector)
virtual returnValue step (const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector)
virtual ~SCPmethod ()

Protected Member Functions

returnValue checkForConvergence ()
returnValue checkForRealTimeMode (const DVector &x0_, const DVector &p_)
returnValue computeHessianMatrix (const BlockMatrix &oldLagrangeGradient, const BlockMatrix &newLagrangeGradient)
virtual returnValue getAlgebraicStates (VariablesGrid &xa_) const
virtual returnValue getAnySensitivities (BlockMatrix &_sens, uint idx) const
virtual returnValue getControls (VariablesGrid &u_) const
virtual returnValue getDifferentialStates (VariablesGrid &xd_) const
virtual returnValue getDisturbances (VariablesGrid &w_) const
virtual returnValue getFirstControl (DVector &u0_) const
uint getNC () const
uint getNP () const
uint getNU () const
uint getNumPoints () const
uint getNW () const
uint getNX () const
uint getNXA () const
virtual double getObjectiveValue () const
virtual returnValue getParameters (VariablesGrid &p_) const
virtual returnValue getParameters (DVector &p_) const
virtual returnValue getSensitivitiesP (BlockMatrix &_sens) const
virtual returnValue getSensitivitiesU (BlockMatrix &_sens) const
virtual returnValue getSensitivitiesW (BlockMatrix &_sens) const
virtual returnValue getSensitivitiesX (BlockMatrix &_sens) const
virtual returnValue getSensitivitiesXA (BlockMatrix &_sens) const
returnValue initializeHessianProjection ()
returnValue printIterate () const
returnValue printIteration ()
returnValue setup ()
virtual returnValue setupLogging ()
returnValue setupRealTimeParameters (const DVector &x0_=emptyConstVector, const DVector &p_=emptyConstVector)
returnValue stopClockAndPrintRuntimeProfile ()

Protected Attributes

BandedCP bandedCP
BandedCPsolverbandedCPsolver
RealClock clock
RealClock clockTotalTime
NLPderivativeApproximationderivativeApproximation
SCPevaluationeval
BooleanType hasPerformedStep
BooleanType isCP
BooleanType isInRealTimeMode
OCPiterate iter
BooleanType needToReevaluate
OCPiterate oldIter
SCPstepscpStep
BlockStatus status
int timeLoggingIdx

Detailed Description

Implements different sequential convex programming methods for solving NLPs.

The class SCPmethod implements different sequential convex programming methods for solving nonlinear programming problems.

Author:
Boris Houska, Hans Joachim Ferreau

Definition at line 67 of file scp_method.hpp.


Constructor & Destructor Documentation

Default constructor.

Definition at line 50 of file scp_method.cpp.

SCPmethod::SCPmethod ( UserInteraction _userInteraction,
const Objective objective_,
const DynamicDiscretization dynamic_discretization_,
const Constraint constraint_,
BooleanType  _isCP = BT_FALSE 
)

Default constructor.

Definition at line 69 of file scp_method.cpp.

SCPmethod::SCPmethod ( const SCPmethod rhs)

Copy constructor (deep copy).

Definition at line 93 of file scp_method.cpp.

SCPmethod::~SCPmethod ( ) [virtual]

Destructor.

Definition at line 124 of file scp_method.cpp.


Member Function Documentation

Definition at line 885 of file scp_method.cpp.

returnValue SCPmethod::checkForRealTimeMode ( const DVector x0_,
const DVector p_ 
) [protected]

Definition at line 962 of file scp_method.cpp.

NLPsolver * SCPmethod::clone ( ) const [virtual]

Implements NLPsolver.

Definition at line 191 of file scp_method.cpp.

returnValue SCPmethod::computeHessianMatrix ( const BlockMatrix oldLagrangeGradient,
const BlockMatrix newLagrangeGradient 
) [protected]

Definition at line 923 of file scp_method.cpp.

returnValue SCPmethod::feedbackStep ( const DVector x0_,
const DVector p_ = emptyConstVector 
) [virtual]

Executes a real-time feedback step

Reimplemented from NLPsolver.

Definition at line 317 of file scp_method.cpp.

returnValue SCPmethod::getAlgebraicStates ( VariablesGrid xa_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1021 of file scp_method.cpp.

returnValue SCPmethod::getAnySensitivities ( BlockMatrix _sens,
uint  idx 
) const [protected, virtual]

Definition at line 1136 of file scp_method.cpp.

returnValue SCPmethod::getControls ( VariablesGrid u_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1050 of file scp_method.cpp.

returnValue SCPmethod::getDifferentialStates ( VariablesGrid xd_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1011 of file scp_method.cpp.

returnValue SCPmethod::getDisturbances ( VariablesGrid w_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1083 of file scp_method.cpp.

returnValue SCPmethod::getFirstControl ( DVector u0_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1060 of file scp_method.cpp.

uint SCPmethod::getNC ( ) const [inline, protected]
uint SCPmethod::getNP ( ) const [inline, protected]
uint SCPmethod::getNU ( ) const [inline, protected]
uint SCPmethod::getNumPoints ( ) const [inline, protected]
uint SCPmethod::getNW ( ) const [inline, protected]
uint SCPmethod::getNX ( ) const [inline, protected]
uint SCPmethod::getNXA ( ) const [inline, protected]
double SCPmethod::getObjectiveValue ( ) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1094 of file scp_method.cpp.

returnValue SCPmethod::getParameters ( VariablesGrid p_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1030 of file scp_method.cpp.

returnValue SCPmethod::getParameters ( DVector p_) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1040 of file scp_method.cpp.

returnValue SCPmethod::getSensitivitiesP ( BlockMatrix _sens) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1115 of file scp_method.cpp.

returnValue SCPmethod::getSensitivitiesU ( BlockMatrix _sens) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1122 of file scp_method.cpp.

returnValue SCPmethod::getSensitivitiesW ( BlockMatrix _sens) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1129 of file scp_method.cpp.

returnValue SCPmethod::getSensitivitiesX ( BlockMatrix _sens) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1102 of file scp_method.cpp.

returnValue SCPmethod::getSensitivitiesXA ( BlockMatrix _sens) const [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 1109 of file scp_method.cpp.

Returns a variance-covariance estimate if possible or an error message otherwise.

Returns:
SUCCESSFUL_RETURN RET_MEMBER_NOT_INITIALISED

Implements NLPsolver.

Definition at line 611 of file scp_method.cpp.

returnValue SCPmethod::init ( VariablesGrid x_init,
VariablesGrid xa_init,
VariablesGrid p_init,
VariablesGrid u_init,
VariablesGrid w_init 
) [virtual]

Initialization.

Implements NLPsolver.

Definition at line 198 of file scp_method.cpp.

Definition at line 945 of file scp_method.cpp.

SCPmethod & SCPmethod::operator= ( const SCPmethod rhs)

Assignment operator (deep copy).

Definition at line 140 of file scp_method.cpp.

Executes a real-time preparation step

Reimplemented from NLPsolver.

Definition at line 384 of file scp_method.cpp.

Executes a real-time preparation step

Reimplemented from NLPsolver.

Definition at line 456 of file scp_method.cpp.

returnValue SCPmethod::printIterate ( ) const [protected]

Prints the actual values of x, xa, p, u, and w.

Definition at line 828 of file scp_method.cpp.

Definition at line 834 of file scp_method.cpp.

Prints the run-time profile. This routine
can be used after an integration run in
order to assess the performance.

Definition at line 623 of file scp_method.cpp.

Sets the reference to be used in the LSQ tracking terms. If the objective
has also non-LSQ terms or no LSQ terms, an error message will be returned
(cf. objective.hpp).
This routine has been designed for real-time applications where the reference
is explicitly time-dependent.

Returns:
SUCCESSFUL_RETURN

Reimplemented from NLPsolver.

Definition at line 567 of file scp_method.cpp.

returnValue SCPmethod::setup ( ) [protected]

Definition at line 667 of file scp_method.cpp.

returnValue SCPmethod::setupLogging ( ) [protected, virtual]

Reimplemented from NLPsolver.

Definition at line 634 of file scp_method.cpp.

Definition at line 978 of file scp_method.cpp.

returnValue SCPmethod::shiftVariables ( double  timeShift = -1.0,
DVector  lastX = emptyVector,
DVector  lastXA = emptyVector,
DVector  lastP = emptyVector,
DVector  lastU = emptyVector,
DVector  lastW = emptyVector 
) [virtual]

Shifts the data for preparating the next real-time step.

Returns:
RET_NOT_YET_IMPLEMENTED

Reimplemented from NLPsolver.

Definition at line 582 of file scp_method.cpp.

returnValue SCPmethod::solve ( const DVector x0_ = emptyConstVector,
const DVector p_ = emptyConstVector 
) [virtual]

Solves current, possibly parametric, optimization problem.

Reimplemented from NLPsolver.

Definition at line 260 of file scp_method.cpp.

returnValue SCPmethod::step ( const DVector x0_ = emptyConstVector,
const DVector p_ = emptyConstVector 
) [virtual]

Executes a complete real-time step.

Reimplemented from NLPsolver.

Definition at line 295 of file scp_method.cpp.

Definition at line 995 of file scp_method.cpp.


Member Data Documentation

Definition at line 267 of file scp_method.hpp.

Definition at line 268 of file scp_method.hpp.

Definition at line 257 of file scp_method.hpp.

Definition at line 258 of file scp_method.hpp.

Definition at line 265 of file scp_method.hpp.

Definition at line 263 of file scp_method.hpp.

Definition at line 273 of file scp_method.hpp.

Definition at line 271 of file scp_method.hpp.

Definition at line 274 of file scp_method.hpp.

Definition at line 260 of file scp_method.hpp.

Definition at line 275 of file scp_method.hpp.

Definition at line 261 of file scp_method.hpp.

Definition at line 264 of file scp_method.hpp.

Definition at line 270 of file scp_method.hpp.

int SCPmethod::timeLoggingIdx [protected]

Definition at line 256 of file scp_method.hpp.


The documentation for this class was generated from the following files:


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 12:01:40