00001 /****************************************************************************** 00002 Copyright (c) 2017, Alexander W Winkler. All rights reserved. 00003 00004 Redistribution and use in source and binary forms, with or without 00005 modification, are permitted provided that the following conditions are met: 00006 00007 * Redistributions of source code must retain the above copyright notice, this 00008 list of conditions and the following disclaimer. 00009 00010 * Redistributions in binary form must reproduce the above copyright notice, 00011 this list of conditions and the following disclaimer in the documentation 00012 and/or other materials provided with the distribution. 00013 00014 * Neither the name of the copyright holder nor the names of its 00015 contributors may be used to endorse or promote products derived from 00016 this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00028 ******************************************************************************/ 00029 00030 #ifndef IFOPT_INCLUDE_OPT_PROBLEM_H_ 00031 #define IFOPT_INCLUDE_OPT_PROBLEM_H_ 00032 00033 #include "variable_set.h" 00034 #include "constraint_set.h" 00035 #include "cost_term.h" 00036 00037 namespace ifopt { 00038 00062 class Problem { 00063 public: 00064 using VecBound = Component::VecBound; 00065 using Jacobian = Component::Jacobian; 00066 using VectorXd = Component::VectorXd; 00067 00071 Problem (); 00072 virtual ~Problem () = default; 00073 00083 void AddVariableSet(VariableSet::Ptr variable_set); 00084 00093 void AddConstraintSet(ConstraintSet::Ptr constraint_set); 00094 00103 void AddCostSet(CostTerm::Ptr cost_set); 00104 00108 void SetVariables(const double* x); 00109 00113 int GetNumberOfOptimizationVariables() const; 00114 00119 bool HasCostTerms() const; 00120 00125 VecBound GetBoundsOnOptimizationVariables() const; 00126 00130 VectorXd GetVariableValues() const; 00131 00135 double EvaluateCostFunction(const double* x); 00136 00140 VectorXd EvaluateCostFunctionGradient(const double* x); 00141 00145 int GetNumberOfConstraints() const; 00146 00150 VecBound GetBoundsOnConstraints() const; 00151 00155 VectorXd EvaluateConstraints(const double* x); 00156 00162 void EvalNonzerosOfJacobian(const double* x, double* values); 00163 00170 Jacobian GetJacobianOfConstraints() const; 00171 00177 void SaveCurrent(); 00178 00182 Composite::Ptr GetOptVariables() const; 00183 00187 void SetOptVariables(int iter); 00188 00192 void SetOptVariablesFinal(); 00193 00197 int GetIterationCount() const { return x_prev.size(); }; 00198 00202 void PrintCurrent() const; 00203 00204 private: 00205 Composite::Ptr variables_; 00206 Composite constraints_; 00207 Composite costs_; 00208 00209 std::vector<VectorXd> x_prev; 00210 00211 VectorXd ConvertToEigen(const double* x) const; 00212 }; 00213 00214 } /* namespace opt */ 00215 00216 00226 #endif /* IFOPT_INCLUDE_OPT_PROBLEM_H_ */