00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00037 #ifndef QPOASES_QPROBLEMB_HPP
00038 #define QPOASES_QPROBLEMB_HPP
00039
00040
00041 #include <Bounds.hpp>
00042
00043
00044
00045 class SolutionAnalysis;
00046
00055 class QProblemB
00056 {
00057
00058 friend class SolutionAnalysis;
00059
00060
00061
00062
00063 public:
00065 QProblemB( );
00066
00068 QProblemB( int _nV
00069 );
00070
00072 QProblemB( const QProblemB& rhs
00073 );
00074
00076 ~QProblemB( );
00077
00079 QProblemB& operator=( const QProblemB& rhs
00080 );
00081
00082
00086 returnValue reset( );
00087
00088
00101 returnValue init( const real_t* const _H,
00102 const real_t* const _g,
00103 const real_t* const _lb,
00105 const real_t* const _ub,
00107 int& nWSR,
00109 const real_t* const yOpt = 0,
00110 real_t* const cputime = 0
00111 );
00112
00113
00126 returnValue init( const real_t* const _H,
00127 const real_t* const _R,
00128 const real_t* const _g,
00129 const real_t* const _lb,
00131 const real_t* const _ub,
00133 int& nWSR,
00135 const real_t* const yOpt = 0,
00136 real_t* const cputime = 0
00137 );
00138
00139
00153 returnValue hotstart( const real_t* const g_new,
00154 const real_t* const lb_new,
00156 const real_t* const ub_new,
00158 int& nWSR,
00160 real_t* const cputime
00161 );
00162
00163
00166 inline returnValue getH( real_t* const _H
00167 ) const;
00168
00171 inline returnValue getG( real_t* const _g
00172 ) const;
00173
00176 inline returnValue getLB( real_t* const _lb
00177 ) const;
00178
00182 inline returnValue getLB( int number,
00183 real_t& value
00184 ) const;
00185
00188 inline returnValue getUB( real_t* const _ub
00189 ) const;
00190
00194 inline returnValue getUB( int number,
00195 real_t& value
00196 ) const;
00197
00198
00201 inline returnValue getBounds( Bounds* const _bounds
00202 ) const;
00203
00204
00207 inline int getNV( ) const;
00208
00211 inline int getNFR( );
00212
00215 inline int getNFX( );
00216
00219 inline int getNFV( ) const;
00220
00223 int getNZ( );
00224
00225
00229 real_t getObjVal( ) const;
00230
00233 real_t getObjVal( const real_t* const _x
00234 ) const;
00235
00239 returnValue getPrimalSolution( real_t* const xOpt
00240 ) const;
00241
00245 returnValue getDualSolution( real_t* const yOpt
00246 ) const;
00247
00248
00251 inline QProblemStatus getStatus( ) const;
00252
00253
00257 inline BooleanType isInitialised( ) const;
00258
00262 inline BooleanType isSolved( ) const;
00263
00267 inline BooleanType isInfeasible( ) const;
00268
00272 inline BooleanType isUnbounded( ) const;
00273
00274
00277 inline PrintLevel getPrintLevel( ) const;
00278
00281 returnValue setPrintLevel( PrintLevel _printlevel
00282 );
00283
00284
00287 inline HessianType getHessianType( ) const;
00288
00291 inline returnValue setHessianType( HessianType _hessianType
00292 );
00293
00294
00295
00296
00297
00298 protected:
00302 returnValue checkForIdentityHessian( );
00303
00307 returnValue setupSubjectToType( );
00308
00313 returnValue setupCholeskyDecomposition( );
00314
00315
00326 returnValue solveInitialQP( const real_t* const xOpt,
00328 const real_t* const yOpt,
00330 const Bounds* const guessedBounds,
00332 int& nWSR,
00334 real_t* const cputime
00335 );
00336
00337
00343 returnValue obtainAuxiliaryWorkingSet( const real_t* const xOpt,
00345 const real_t* const yOpt,
00347 const Bounds* const guessedBounds,
00348 Bounds* auxiliaryBounds
00350 ) const;
00351
00359 returnValue setupAuxiliaryWorkingSet( const Bounds* const auxiliaryBounds,
00360 BooleanType setupAfresh
00362 );
00363
00366 returnValue setupAuxiliaryQPsolution( const real_t* const xOpt,
00368 const real_t* const yOpt
00370 );
00371
00376 returnValue setupAuxiliaryQPgradient( );
00377
00383 returnValue setupAuxiliaryQPbounds( BooleanType useRelaxation
00384 );
00385
00386
00390 returnValue addBound( int number,
00391 SubjectToStatus B_status,
00392 BooleanType updateCholesky
00393 );
00394
00399 returnValue removeBound( int number,
00400 BooleanType updateCholesky
00401 );
00402
00403
00407 returnValue backsolveR( const real_t* const b,
00408 BooleanType transposed,
00409 real_t* const a
00410 );
00411
00416 returnValue backsolveR( const real_t* const b,
00417 BooleanType transposed,
00418 BooleanType removingBound,
00419 real_t* const a
00420 );
00421
00422
00425 returnValue hotstart_determineDataShift(const int* const FX_idx,
00426 const real_t* const g_new,
00427 const real_t* const lb_new,
00428 const real_t* const ub_new,
00429 real_t* const delta_g,
00430 real_t* const delta_lb,
00431 real_t* const delta_ub,
00432 BooleanType& Delta_bB_isZero
00433 );
00434
00435
00440 BooleanType areBoundsConsistent( const real_t* const delta_lb,
00441 const real_t* const delta_ub
00442 ) const;
00443
00444
00448 returnValue setupQPdata( const real_t* const _H,
00449 const real_t* const _R,
00450 const real_t* const _g,
00451 const real_t* const _lb,
00453 const real_t* const _ub
00455 );
00456
00457
00460 inline returnValue setH( const real_t* const H_new
00461 );
00462
00465 inline returnValue setG( const real_t* const g_new
00466 );
00467
00470 inline returnValue setLB( const real_t* const lb_new
00471 );
00472
00476 inline returnValue setLB( int number,
00477 real_t value
00478 );
00479
00482 inline returnValue setUB( const real_t* const ub_new
00483 );
00484
00488 inline returnValue setUB( int number,
00489 real_t value
00490 );
00491
00492
00495 inline void computeGivens( real_t xold,
00496 real_t yold,
00497 real_t& xnew,
00498 real_t& ynew,
00499 real_t& c,
00500 real_t& s
00501 ) const;
00502
00505 inline void applyGivens( real_t c,
00506 real_t s,
00507 real_t xold,
00509 real_t yold,
00511 real_t& xnew,
00513 real_t& ynew
00515 ) const;
00516
00517
00518
00519
00520
00521 private:
00525 returnValue hotstart_determineStepDirection(const int* const FR_idx,
00526 const int* const FX_idx,
00527 const real_t* const delta_g,
00528 const real_t* const delta_lb,
00529 const real_t* const delta_ub,
00530 BooleanType Delta_bB_isZero,
00531 real_t* const delta_xFX,
00532 real_t* const delta_xFR,
00533 real_t* const delta_yFX
00534 );
00535
00538 returnValue hotstart_determineStepLength( const int* const FR_idx,
00539 const int* const FX_idx,
00540 const real_t* const delta_lb,
00541 const real_t* const delta_ub,
00542 const real_t* const delta_xFR,
00543 const real_t* const delta_yFX,
00544 int& BC_idx,
00545 SubjectToStatus& BC_status
00546 );
00547
00554 returnValue hotstart_performStep( const int* const FR_idx,
00555 const int* const FX_idx,
00556 const real_t* const delta_g,
00557 const real_t* const delta_lb,
00558 const real_t* const delta_ub,
00559 const real_t* const delta_xFX,
00560 const real_t* const delta_xFR,
00561 const real_t* const delta_yFX,
00562 int BC_idx,
00563 SubjectToStatus BC_status
00564 );
00565
00566
00567 #ifdef PC_DEBUG
00568
00571 returnValue printIteration( int iteration,
00572 int BC_idx,
00573 SubjectToStatus BC_status
00574 );
00575
00576 #endif
00577
00578
00584 returnValue checkKKTconditions( );
00585
00586
00587
00588
00589
00590 protected:
00591 real_t H[NVMAX*NVMAX];
00592 BooleanType hasHessian;
00594 real_t g[NVMAX];
00595 real_t lb[NVMAX];
00596 real_t ub[NVMAX];
00598 Bounds bounds;
00600 real_t R[NVMAX*NVMAX];
00601 BooleanType hasCholesky;
00603 real_t x[NVMAX];
00604 real_t y[NVMAX+NCMAX];
00606 real_t tau;
00608 QProblemStatus status;
00610 BooleanType infeasible;
00611 BooleanType unbounded;
00613 HessianType hessianType;
00615 PrintLevel printlevel;
00617 int count;
00618 };
00619
00620
00621 #include <QProblemB.ipp>
00622
00623 #endif
00624
00625
00626
00627
00628