25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_ 26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_ 34 #include <IpIpoptApplication.hpp> 48 class SolverIpopt :
public NlpSolverInterface
50 friend class IpoptWrapper;
53 using Ptr = std::shared_ptr<SolverIpopt>;
54 using UPtr = std::unique_ptr<SolverIpopt>;
65 bool initialize(OptimizationProblemInterface* problem =
nullptr)
override;
67 SolverStatus solve(OptimizationProblemInterface& problem,
bool new_structure =
true,
bool new_run =
true,
double* obj_value =
nullptr)
override;
76 bool setLinearSolverByName(
const std::string& solver_name);
77 std::string getLinearSolverByName();
79 bool setRelTolerance(
double tolerance);
80 double getRelTolerance()
const;
82 bool setDualInfTolerance(
double tolerance);
83 double getDualInfTolerance()
const;
85 bool setConstrViolTolerance(
double tolerance);
86 double getConstrViolTolerance()
const;
88 bool setComplInfTolerance(
double tolerance);
89 double getComplInfTolerance()
const;
91 bool setMuStrategyAdaptive(
bool enabled);
92 bool isMuStrategyAdaptive()
const;
94 bool setHessianApproxExact(
bool enabled);
95 bool isHessianApproxExact()
const;
97 bool setWarmStartInitPoint(
bool enabled);
98 bool isWarmStartInitPoint()
const;
100 bool setMehrotraAlgorithm(
bool enabled);
101 bool isMehrotraAlgorithm()
const;
103 bool setPrintLevel(
int print_level);
104 int getPrintLevel()
const;
106 bool setNlpAutoScaling(
bool enabled);
107 bool isNlpAutoScaling()
const;
109 void setIterations(
int iterations) { _iterations = iterations; }
110 int getIterations()
const {
return _iterations; }
112 void setMaxCpuTime(
double max_cpu_time) { _max_cpu_time = max_cpu_time; }
113 double getMaxCpuTime()
const {
return _max_cpu_time; }
115 bool setCheckDerivativesForNan(
bool enabled);
116 bool isCheckDerivativesForNan()
const;
118 bool setDerivativeTest(
bool first_order,
bool second_order);
119 void isDerivativeTest(
bool& first_order,
bool& second_order)
const;
122 bool setIpoptOptionString(
const std::string& param,
const std::string& option);
123 bool setIpoptOptionInt(
const std::string& param,
int option);
124 bool setIpoptOptionNumeric(
const std::string& param,
double option);
126 void setCacheFirstOrderDerivatives(
bool active) { _cache_first_order_derivatives = active; }
130 void clear()
override;
134 #ifdef MESSAGE_SUPPORT 136 void toMessage(corbo::messages::NlpSolver& message)
const override;
138 void fromMessage(
const corbo::messages::NlpSolver& message, std::stringstream* issues =
nullptr)
override;
142 SolverStatus convertIpoptToNlpSolverStatus(Ipopt::ApplicationReturnStatus ipopt_status)
const;
145 Ipopt::SmartPtr<IpoptWrapper> _ipopt_nlp;
146 Ipopt::SmartPtr<Ipopt::IpoptApplication> _ipopt_app;
148 int _nnz_jac_constraints = 0;
149 int _nnz_h_lagrangian = 0;
150 int _nnz_hes_obj = 0;
152 int _nnz_hes_ineq = 0;
154 Eigen::VectorXd _lambda_cache;
155 Eigen::VectorXd _zl_cache;
156 Eigen::VectorXd _zu_cache;
158 Eigen::VectorXd _grad_f_cache;
159 Eigen::VectorXd _jac_constr_cache;
163 double _max_cpu_time = -1;
164 int _iterations = 100;
166 double _last_obj_value = -1;
168 bool _cache_first_order_derivatives =
false;
172 bool _initialized =
false;
174 int _param_msg_received =
false;
191 using Ptr = std::shared_ptr<SolverIpopt>;
192 using UPtr = std::unique_ptr<SolverIpopt>;
217 #ifdef MESSAGE_SUPPORT 219 void toMessage(corbo::messages::NlpSolver& )
const override {
printWarning(); }
221 void fromMessage(
const corbo::messages::NlpSolver& , std::stringstream* issues)
override 223 if (issues) *issues <<
"SolverIPOPT cannot be selected since it is not installed properly." << std::endl;
236 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_SOLVER_NLP_SOLVER_IPOPT_H_ void clear() override
Clear internal caches.
SolverStatus solve(OptimizationProblemInterface &problem, bool new_structure=true, bool new_run=true, double *obj_value=nullptr) override
Solve the provided optimization problem.
void printWarning() const
#define PRINT_WARNING(msg)
Print msg-stream.
std::unique_ptr< NlpSolverInterface > UPtr
Interface to the external interior point solver IPOPT.
Generic interface for optimization problem definitions.
bool initialize(OptimizationProblemInterface *problem=nullptr) override
Initialize the solver w.r.t. a given optimization problem.
std::unique_ptr< SolverIpopt > UPtr
bool isLsqSolver() const override
Return true if the solver onyl supports costs in lsq form.
std::shared_ptr< NlpSolverInterface > Ptr
NlpSolverInterface::Ptr getInstance() const override
Return a newly created instance of the current solver.
Generic interface for solver implementations.
std::shared_ptr< SolverIpopt > Ptr
#define FACTORY_REGISTER_NLP_SOLVER(type)