Minotaur 0.4.1
Docs for developers
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
Minotaur::Problem Class Reference
Inheritance diagram for Minotaur::Problem:
Inheritance graph
[legend]
Collaboration diagram for Minotaur::Problem:
Collaboration graph
[legend]

Public Member Functions

 Problem (EnvPtr env)
 Default constructor.
 
virtual ~Problem ()
 Destroy.
 
virtual void addToCons (ConstraintPtr cons, double c)
 Add 'c' to both lb and ub of a constraint.
 
virtual void addToObj (LinearFunctionPtr lf)
 Add a linear function to the objective.
 
virtual void addToObj (double cb)
 Add a constant term to the objective.
 
virtual void calculateSize (bool shouldRedo=false)
 Fill up the statistics about the size of the problem into size_.
 
virtual void changeBoundByInd (UInt ind, BoundType lu, double new_val)
 Change a bound (lower or upper) on a variable with ID=id.
 
virtual void changeBoundByInd (UInt ind, double new_lb, double new_ub)
 Change both bounds (lower and upper) on a variable with ID=id.
 
virtual void changeBound (VariablePtr var, BoundType lu, double new_val)
 Change a bound (lower or upper) on a variable 'var'.
 
virtual void changeBound (VariablePtr var, double new_lb, double new_ub)
 Change lower and upper bounds on the variable 'var'.
 
virtual void changeBound (ConstraintPtr con, BoundType lu, double new_val)
 Change a bound (lower or upper) on a constraint 'con'.
 
virtual void changeBound (ConstraintPtr con, double new_lb, double new_ub)
 Change lower and upper bounds on the constraint 'con'.
 
virtual void changeConstraint (ConstraintPtr con, LinearFunctionPtr lf, double lb, double ub)
 Change the linear function, and the bounds of a constraint. More...
 
virtual void changeConstraint (ConstraintPtr con, NonlinearFunctionPtr nlf)
 Change the nonlinear function and bounds of a constraint. More...
 
virtual void changeObj (FunctionPtr f, double cb)
 Replace the objective function with a new function. More...
 
virtual int checkConVars () const
 Check whether variables used in the constraints belong to the problem or not. More...
 
virtual void classifyCon ()
 
ProblemPtr clone (EnvPtr env) const
 Clone the given Problem class. Jacobian and Hessian in the cloned problem are NULL. More...
 
ProblemPtr shuffle (bool varshuff, bool conshuff, EnvPtr env)
 shuffle variables and constraints while making a clone of the problem More...
 
void cg2qf ()
 Convert all quadratic forms that are stored as CGraph into QuadraticFunction. The order of constraints changes after this conversion.
 
virtual ConstraintConstIterator consBegin () const
 Iterate over constraints. Returns the 'begin' iterator.
 
virtual ConstraintConstIterator consEnd () const
 Iterate over constraints. Returns the 'end' iterator.
 
virtual void delMarkedCons ()
 Delete marked constraints.
 
virtual void delMarkedVars (bool keep=false)
 
virtual ProblemType findType ()
 Return what type of problem it is. May result in re-calculation of the problem size.
 
virtual ConstraintPtr getConstraint (UInt index) const
 Return a pointer to the constraint with a given index.
 
virtual DoubleVector * getDebugSol () const
 Give a pointer to the debug solution. More...
 
virtual HessianOfLagPtr getHessian () const
 Return the hessian of the lagrangean. Could be NULL.
 
virtual JacobianPtr getJacobian () const
 Return the jacobian. Could be NULL.
 
virtual UInt getNumCons () const
 Return the number of constraints.
 
virtual UInt getNumDCons () const
 Return the number of constraints marked for deletion.
 
virtual UInt getNumDVars () const
 Return the number of variables marked for deletion.
 
virtual UInt getNumHessNnzs () const
 Return the number of non-zeros in the hessian of the lagrangean of the problem. More...
 
virtual UInt getNumJacNnzs () const
 Return the number of non zerors in the jacobian of the constraints.
 
UInt getNumLinCons ()
 Return the number of linear constraints in the problem.
 
UInt getNumSOS1 ()
 Return the number of SOS Type 1 constraints.
 
UInt getNumSOS2 ()
 Return the number of SOS Type 2 constraints.
 
virtual UInt getNumVars () const
 Return the number of variables.
 
virtual ObjectivePtr getObjective () const
 Return a pointer to the objective Function.
 
double getObjValue (const double *x, int *err) const
 Return the value of objective function at given point x.
 
ConstProblemSizePtr getSize () const
 Fill up the statistics about the size of the problem into size_.
 
double getSizeEstimate ()
 Calculate and return a measure of the size of the problem.
 
virtual VariablePtr getVariable (UInt index) const
 Return a pointer to the variable with a given index.
 
virtual bool hasNativeDer () const
 Return true if the derivative is available through Minotaur's own routines for storing nonlinear functions.
 
virtual bool isDebugSolFeas (double atol, double rtol)
 Returns true if the debug solution is cut off by the constraints of the problem.
 
virtual bool isLinear ()
 Returns true if the problem has only linear constraints and linear objectives.
 
virtual bool isMarkedDel (ConstConstraintPtr con)
 Return true if a constraint is marked deleted.
 
virtual bool isMarkedDel (ConstVariablePtr var)
 Return true if a constraint is marked deleted.
 
virtual bool isQP ()
 Returns true if the problem has (1) linear or quadratic objective, and (2) linear constraints only.
 
virtual bool isQuadratic ()
 Returns true if the problem has only linear or quadratic constraints and linear or quadratic objectives. Returns false if a problem is linear. Returns false if problem is nonlinear.
 
virtual void markDelete (ConstraintPtr con)
 Mark a constraint for deleting. More...
 
bool checkQuadCond (const ConstraintStats &stats)
 
bool checkCoeffCond (const ConstraintStats &stats, bool positive)
 
virtual void markDelete (VariablePtr var)
 Mark a variable as deleted. More...
 
virtual void negateObj ()
 The objective is multiplied by -1.
 
virtual VariablePtr newBinaryVariable ()
 Add a new binary variable and return a pointer to it. A name is automatically generated by default.
 
virtual VariablePtr newBinaryVariable (std::string name)
 Add a new binary variable. More...
 
virtual ConstraintPtr newConstraint (FunctionPtr f, double lb, double ub)
 Add a new constraint and return a pointer to it. A name is automatically generated by default. More...
 
virtual ConstraintPtr newConstraint (FunctionPtr f, double lb, double ub, std::string name)
 Add a new constraint and return a pointer to it. More...
 
virtual ObjectivePtr newObjective (FunctionPtr f, double cb, ObjectiveType otyp)
 Add a new objective. A name is automatically generated by default. More...
 
virtual ObjectivePtr newObjective (double cb, ObjectiveType otyp)
 
virtual ObjectivePtr newObjective (FunctionPtr f, double cb, ObjectiveType otyp, std::string name)
 Add a new objective. More...
 
virtual SOSPtr newSOS (int n, SOSType type, const double *weights, const VarVector &vars, int priority, std::string name)
 Add a new SOS constraint with a name. More...
 
virtual SOSPtr newSOS (int n, SOSType type, const double *weights, const VarVector &vars, int priority)
 Add a new SOS constraint (name generated automatically). More...
 
virtual VariablePtr newVariable (VarSrcType stype=VarOrig)
 Add a new continuous, unbounded variable to the Problem. More...
 
virtual VariablePtr newVariable (double lb, double ub, VariableType vtype, VarSrcType=VarOrig)
 Add a new variable with bounds, type. A name is automatically generated by default. More...
 
virtual VariablePtr newVariable (double lb, double ub, VariableType vtype, std::string name, VarSrcType=VarOrig)
 Add a new variable. More...
 
virtual void newVariables (VariableConstIterator v_begin, VariableConstIterator v_end, VarSrcType stype=VarOrig)
 Clone the variables pointed by the iterators and add them. More...
 
virtual void prepareForSolve ()
 Setup problem data-structures for solving it. More...
 
virtual void objToCons ()
 
virtual void removeObjective ()
 Remove objective from the Problem.
 
virtual QuadraticFunctionPtr removeQuadFromObj ()
 Remove the quadratic part of objective and return it.
 
virtual NonlinearFunctionPtr removeNonlinFromObj ()
 
virtual void resetDer ()
 
virtual void resConTypCnt ()
 
virtual void reverseSense (ConstraintPtr cons)
 Reverse the sense of a constraint. More...
 
virtual void setDebugSol (const DoubleVector &x)
 Set a solution that can be checked for accidental cutting off by cuts, branching, reformulations etc. More...
 
virtual void setEngine (Engine *engine)
 Set the engine that is used to solve this problem. More...
 
virtual void setHessian (HessianOfLagPtr hessian)
 Add a pointer to the hessian of the Lagrangean. More...
 
virtual void setInitialPoint (const double *x)
 Set an initial point. More...
 
virtual void setInitialPoint (const double *x, size_t k)
 Set an initial point. More...
 
virtual void setInitVal (VariablePtr v, double val)
 
virtual void setInitValByInd (UInt ind, double val)
 
virtual void setJacobian (JacobianPtr jacobian)
 Set the jacobian of the constraints. More...
 
void setNativeDer ()
 Ask Problem to construct its own jacobian and hessian using Minotaur's native code for nonlinear functions.
 
virtual void setVarType (VariablePtr var, VariableType type)
 Change the variable type. More...
 
virtual SOSConstIterator sos1Begin () const
 
virtual SOSConstIterator sos1End () const
 
virtual SOSConstIterator sos2Begin () const
 
virtual SOSConstIterator sos2End () const
 
virtual void subst (VariablePtr out, VariablePtr in, double rat=1.0)
 Substitute a variable 'out' with the variable 'in' through out the problem. More...
 
virtual void unsetEngine ()
 Should be called in the Engine's destructor.
 
virtual VariableConstIterator varsBegin () const
 Iterate over variables.
 
virtual VariableConstIterator varsEnd () const
 Iterate over variables.
 
virtual void write (std::ostream &out, std::streamsize out_p=6) const
 only for debugging, developing etc.
 
virtual void writeSize (std::ostream &out) const
 Write the problem size to logger_.
 
void statistics (std::ostream &out) const
 

Public Attributes

const double INFTY = std::numeric_limits<double>::infinity()
 

Protected Member Functions

bool isAggregation_ (ConstraintPtr c)
 
bool isPrecedence_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isVariableBound_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isSetPartitioning_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isSetPacking_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isSetCovering_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isCardinality_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isInvariantKnapsack_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isEquationKnapsack_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isBinPacking_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isKnapsack_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isIntegerKnapsack_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isMixedBinary_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isNoSpecificStructure_ (ConstraintPtr c)
 
bool isDiagonalQuadratic_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isSimpleBall_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isEllipsoid_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isComplementEllipsoid_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isComplementSimpleBall_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isSocSimple_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isPureBilinear_ (ConstraintPtr c, const ConstraintStats &stats)
 
bool isOtherQuadType_ (ConstraintPtr c, const ConstraintStats &stats)
 
void printConstraintStatistics_ ()
 
void printConstraintStatisticsQuad_ ()
 
void lockNum_ ()
 
virtual void countConsTypes_ ()
 Count the types of constraints and fill the values in size_.
 
virtual void countObjTypes_ ()
 Count the types of objectives and fill the values in size_.
 
virtual void countVarTypes_ ()
 Fill up the size_ with number of variables of each type.
 
virtual void findVarFunTypes_ ()
 Update the function types of all variables based on whether they appear as linear, quadratic or nonlinear in each objective and constraint.
 
bool isPolyp_ ()
 
void setIndex_ (VariablePtr v, UInt i)
 

Protected Attributes

ConstraintVector cons_
 Vector of constraints.
 
bool consModed_
 Flag that is turned on if the constraints are added or modified. More...
 
DoubleVector * debugSol_
 A solution to be used for debugging against accidentally cutting of feasible points.
 
Engineengine_
 Engine that must be updated if problem is loaded to it, could be null.
 
HessianOfLagPtr hessian_
 Pointer to the hessian of the lagrangean. Could be NULL.
 
JacobianPtr jacobian_
 Pointer to the jacobian of constraints. Can be NULL.
 
LoggerPtr logger_
 Pointer to the log manager. All output messages are sent to it.
 
bool nativeDer_
 If true, set up our own Hessian and Jacobian.
 
UInt nextCId_
 ID of the next constraint.
 
int nextSId_
 ID of the next SOS constraint.
 
UInt nextVId_
 ID of the next variable.
 
UInt numDCons_
 Number of constraints marked for deletion.
 
UInt numDVars_
 Number of variables marked for deletion.
 
ObjectivePtr obj_
 Objective, could be NULL.
 
ProblemSizePtr size_
 Size statistics for this Problem.
 
SOSVector sos1_
 SOS1 constraints.
 
SOSVector sos2_
 SOS2 constraints.
 
VarVector vars_
 Vector of variables.
 
VarVector varsRem_
 Vector of variables removed from the problem but not yet freed from memory.
 
bool varsModed_
 True if variables delete, added or their bounds changed.
 

Static Protected Attributes

static const std::string me_ = "Problem: "
 For logging.
 

Member Function Documentation

◆ changeConstraint() [1/2]

void Problem::changeConstraint ( ConstraintPtr  con,
LinearFunctionPtr  lf,
double  lb,
double  ub 
)
virtual

Change the linear function, and the bounds of a constraint.

Parameters
[in]conOriginal constraint that is to be changed.
[in]lfThe new linear function.
[in]lbThe new lower bound.
[in]ubThe new upper bound.

◆ changeConstraint() [2/2]

void Problem::changeConstraint ( ConstraintPtr  con,
NonlinearFunctionPtr  nlf 
)
virtual

Change the nonlinear function and bounds of a constraint.

Parameters
[in]conOriginal constraint that is to be changed.
[in]nlfThe new nonlinear function.

◆ changeObj()

void Problem::changeObj ( FunctionPtr  f,
double  cb 
)
virtual

Replace the objective function with a new function.

Parameters
[in]fThe new obejctive function. f is cloned. If f is modified after this call, it won't affect the objective.
[in]cbThe new objective constant.

◆ checkConVars()

int Problem::checkConVars ( ) const
virtual

Check whether variables used in the constraints belong to the problem or not.

This is a sanity check, used only for debugging.

Returns
1 if the check failed, 0 if passed.

◆ clone()

ProblemPtr Problem::clone ( EnvPtr  env) const

Clone the given Problem class. Jacobian and Hessian in the cloned problem are NULL.

The variables are created. If the functions are stored in native format, they are also cloned. Problem size and the initial point are cloned as well.

Parameters
[in]envPointer to environment for the clone.

◆ delMarkedVars()

void Problem::delMarkedVars ( bool  keep = false)
virtual

Remove marked variables from the problem.

Parameters
[in]keepIf false, the variable pointer is freed from memory. If true, then it is not deleted, and can possibly be revisited (e.g. for restoring variables in postsolve). Default is false.

◆ getDebugSol()

DoubleVector * Problem::getDebugSol ( ) const
virtual

Give a pointer to the debug solution.

\Returns null if there is none, otherwise a pointer to a vector of doubles.

◆ getNumHessNnzs()

UInt Problem::getNumHessNnzs ( ) const
virtual

Return the number of non-zeros in the hessian of the lagrangean of the problem.

The lagrangean is defined as: \sigma . f(x) + \sum_{i=0}^{m-1}\lambda_i . g_i(x), where \sigma \in R^1 and \lambda \in R^m are the dual multipliers. The hessian, w.r.t. x, is thus a square symmetric matrix. usually the multipliers are provided by NLP solvers. Such solvers may require during initialization, the number of non-zeros in the lower triangular of the hessian.

◆ markDelete() [1/2]

void Problem::markDelete ( ConstraintPtr  con)
virtual

Mark a constraint for deleting.

The constraint is not deleted, just marked. Call Problem::delMarkedCons() to actually delete all the marked constraints.

Parameters
[in]conThe constraint to be marked.

◆ markDelete() [2/2]

void Problem::markDelete ( VariablePtr  var)
virtual

Mark a variable as deleted.

The variable is not deleted, just marked. Call Problem::delMarkedVars() to actually delete all the marked variables.

Parameters
[in]varThe variable to be marked.

◆ newBinaryVariable()

VariablePtr Problem::newBinaryVariable ( std::string  name)
virtual

Add a new binary variable.

Parameters
[in]nameThe predefined name for this variable.

◆ newConstraint() [1/2]

ConstraintPtr Problem::newConstraint ( FunctionPtr  f,
double  lb,
double  ub 
)
virtual

Add a new constraint and return a pointer to it. A name is automatically generated by default.

Parameters
[in]fPointer to the Function in the constraint. It is not cloned. The pointer is saved as it is.
[in]lbThe lower bound of the constraint. May be -INFINITY.
[in]ubThe upper bound of the constraint. May be +INFINITY.

◆ newConstraint() [2/2]

ConstraintPtr Problem::newConstraint ( FunctionPtr  f,
double  lb,
double  ub,
std::string  name 
)
virtual

Add a new constraint and return a pointer to it.

Parameters
[in]fPointer to the Function in the constraint. It is not cloned. The pointer is saved as it is.
[in]lbThe lower bound of the constraint. May be -INFINITY.
[in]ubThe upper bound of the constraint. May be +INFINITY.
[in]nameThe name for the constraint.

◆ newObjective() [1/2]

ObjectivePtr Problem::newObjective ( FunctionPtr  f,
double  cb,
ObjectiveType  otyp 
)
virtual

Add a new objective. A name is automatically generated by default.

Parameters
[in]fPointer to the Function in the objective. It is not cloned. The pointer is saved as it is.
[in]cbThe constant term in the objective function.
[in]otypWhether the objective is to Minimize or Maximize.

◆ newObjective() [2/2]

ObjectivePtr Problem::newObjective ( FunctionPtr  f,
double  cb,
ObjectiveType  otyp,
std::string  name 
)
virtual

Add a new objective.

Parameters
[in]fPointer to the Function in the objective. It is not cloned. The pointer is saved as it is.
[in]cbThe constant term in the objective function.
[in]otypWhether the objective is to Minimize or Maximize.
[in]nameThe name for the objective function.
Returns
Pointer to the newly added objective function.

◆ newSOS() [1/2]

SOSPtr Problem::newSOS ( int  n,
SOSType  type,
const double *  weights,
const VarVector &  vars,
int  priority 
)
virtual

Add a new SOS constraint (name generated automatically).

Parameters
[in]nNumber of variables in this SOS constraint.
[in]typeSOS1 (SOS type 1) or SOS2 (SOS type 2).
[in]weightsValues of coefficients of variables in the SOS constraint or just relative weights.
[in]varsVariables in the constraint.
[in]priorityThe priority provided by the user for this constraint.
Returns
Pointer to the newly added SOS data.

◆ newSOS() [2/2]

SOSPtr Problem::newSOS ( int  n,
SOSType  type,
const double *  weights,
const VarVector &  vars,
int  priority,
std::string  name 
)
virtual

Add a new SOS constraint with a name.

Parameters
[in]nNumber of variables in this SOS constraint.
[in]typeSOS1 (SOS type 1) or SOS2 (SOS type 2).
[in]weightsValues of coefficients of variables in the SOS constraint or just relative weights.
[in]varsVariables in the constraint.
[in]priorityThe priority provided by the user for this constraint.
[in]nameThe name provided by the user for this SOS.
Returns
Pointer to the newly added SOS data.

◆ newVariable() [1/3]

VariablePtr Problem::newVariable ( double  lb,
double  ub,
VariableType  vtype,
std::string  name,
VarSrcType  stype = VarOrig 
)
virtual

Add a new variable.

Parameters
[in]lbThe lower bound on the variable. May be -INFINITY.
[in]ubThe upper bound on the variable. May be +INFINITY.
[in]vtypeType of the variable: Integer, Continuous, Binary.
[in]nameName of the variable.
[in]stypeThe source of the variable

◆ newVariable() [2/3]

VariablePtr Problem::newVariable ( double  lb,
double  ub,
VariableType  vtype,
VarSrcType  stype = VarOrig 
)
virtual

Add a new variable with bounds, type. A name is automatically generated by default.

Parameters
[in]lbThe lower bound on the variable. May be -INFINITY.
[in]ubThe upper bound on the variable. May be +INFINITY.
[in]vtypeType of the variable: Integer, Continuous, Binary.
[in]stypeThe source of the variable

◆ newVariable() [3/3]

VariablePtr Problem::newVariable ( VarSrcType  stype = VarOrig)
virtual

Add a new continuous, unbounded variable to the Problem.

Parameters
[in]stypeThe source of the variable

◆ newVariables()

void Problem::newVariables ( VariableConstIterator  v_begin,
VariableConstIterator  v_end,
VarSrcType  stype = VarOrig 
)
virtual

Clone the variables pointed by the iterators and add them.

Given starting and stopping iterators of variables, clone these variables and add the copies to this problem. Do not add them to any constraints or objectives. The IDs are not copied.

Parameters
[in]v_beginThe 'begin' iterator of the variable vector.
[in]v_endThe 'end' iterator of the variable vector.
[in]stypeThe source of the variables

◆ objToCons()

void Problem::objToCons ( )
virtual

Move the nonlinear part of the objective function to constraints set using an auxiliary variable

◆ prepareForSolve()

void Problem::prepareForSolve ( )
virtual

Setup problem data-structures for solving it.

Prepare necessary data structures for the next solve. e.g. if constraints have been modified, then re-evalate the sparsity pattern of Jacobian and Hessian.

◆ resetDer()

void Problem::resetDer ( )
virtual

Remove the jacobian and hessian data structures. Useful when you want to re-compute the derivatives after a problem has been modified.

◆ reverseSense()

void Problem::reverseSense ( ConstraintPtr  cons)
virtual

Reverse the sense of a constraint.

Parameters
[in]consThe constraint whose sense has to be reversed.

◆ setDebugSol()

void Problem::setDebugSol ( const DoubleVector &  x)
virtual

Set a solution that can be checked for accidental cutting off by cuts, branching, reformulations etc.

Parameters
[in]xA vector of double values in the same order as variables in the problem.

◆ setEngine()

void Problem::setEngine ( Engine engine)
virtual

Set the engine that is used to solve this problem.

The problem contains a pointer to the engine so that whenever the problem is modified, the engine also gets the modifications. This function sets the engine that must be modified whenever the problem is modified.

Parameters
[in]engineThe engine pointer.

◆ setHessian()

void Problem::setHessian ( HessianOfLagPtr  hessian)
virtual

Add a pointer to the hessian of the Lagrangean.

Parameters
[in]hessianPointer to the HessianOfLag object.

◆ setInitialPoint() [1/2]

void Problem::setInitialPoint ( const double *  x)
virtual

Set an initial point.

Initial point is used by some engines like IpoptEngine. If the initial point has already been set before, it is overwritten by the new point.

Parameters
[in]xAn array of double values containing the coordinates of the initial point.

◆ setInitialPoint() [2/2]

void Problem::setInitialPoint ( const double *  x,
size_t  k 
)
virtual

Set an initial point.

Same as function Problem::setInitialPoint, but only set values for the first 'k' variables. Put in because of AMPL's defined variables.

Parameters
[in]xAn array of double values containing the coordinates of the initial point.
[in]kThe first 'k' variables will be initialized.

◆ setJacobian()

void Problem::setJacobian ( JacobianPtr  jacobian)
virtual

Set the jacobian of the constraints.

Parameters
[in]jacobianPointer to the Jacobian object.

◆ setVarType()

void Problem::setVarType ( VariablePtr  var,
VariableType  type 
)
virtual

Change the variable type.

Parameters
[in]varThe variable pointer whose type needs to be changed.
[in]typeThe new VariableType.

◆ shuffle()

ProblemPtr Problem::shuffle ( bool  varshuff,
bool  conshuff,
EnvPtr  env 
)

shuffle variables and constraints while making a clone of the problem

Parameters
[in]varshuffIf true, the variables are to be shuffled
[in]conshuffIf true, the constraints are to be shuffled
[in]envEnvironment pointer for the cloned problem

◆ subst()

void Problem::subst ( VariablePtr  out,
VariablePtr  in,
double  rat = 1.0 
)
virtual

Substitute a variable 'out' with the variable 'in' through out the problem.

Parameters
[in]outThe variable that is to be substituted out.
[in]inThe variable that replaces the variable 'out'.
[in]ratThe ratio of substitution. $v_{in} = rat \times v_{out}$.

Member Data Documentation

◆ consModed_

bool Minotaur::Problem::consModed_
protected

Flag that is turned on if the constraints are added or modified.

When the problem is changed, say constraints are added or deleted, all associated changes do not happen at that time. For example, when new constraint is added, the hessian and jacobian do not change. This variable is true if constraints have changed since the last time all changes were applied.


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

Minotaur source code documented by Doxygen 1.9.4 on Thu Apr 24 2025