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 00054 #include <ifopt/variable_set.h> 00055 #include <ifopt/constraint_set.h> 00056 #include <ifopt/cost_term.h> 00057 00058 namespace ifopt { 00059 using Eigen::Vector2d; 00060 00061 00062 class ExVariables : public VariableSet { 00063 public: 00064 // Every variable set has a name, here "var_set1". this allows the constraints 00065 // and costs to define values and Jacobians specifically w.r.t this variable set. 00066 ExVariables() : ExVariables("var_set1") {}; 00067 ExVariables(const std::string& name) : VariableSet(2, name) 00068 { 00069 // the initial values where the NLP starts iterating from 00070 x0_ = 3.5; 00071 x1_ = 1.5; 00072 } 00073 00074 // Here is where you can transform the Eigen::Vector into whatever 00075 // internal representation of your variables you have (here two doubles, but 00076 // can also be complex classes such as splines, etc.. 00077 void SetVariables(const VectorXd& x) override 00078 { 00079 x0_ = x(0); 00080 x1_ = x(1); 00081 }; 00082 00083 // Here is the reverse transformation from the internal representation to 00084 // to the Eigen::Vector 00085 VectorXd GetValues() const override 00086 { 00087 return Vector2d(x0_, x1_); 00088 }; 00089 00090 // Each variable has an upper and lower bound set here 00091 VecBound GetBounds() const override 00092 { 00093 VecBound bounds(GetRows()); 00094 bounds.at(0) = Bounds(-1.0, 1.0); 00095 bounds.at(1) = NoBound; 00096 return bounds; 00097 } 00098 00099 private: 00100 double x0_, x1_; 00101 }; 00102 00103 00104 class ExConstraint : public ConstraintSet { 00105 public: 00106 ExConstraint() : ExConstraint("constraint1") {} 00107 00108 // This constraint set just contains 1 constraint, however generally 00109 // each set can contain multiple related constraints. 00110 ExConstraint(const std::string& name) : ConstraintSet(1, name) {} 00111 00112 // The constraint value minus the constant value "1", moved to bounds. 00113 VectorXd GetValues() const override 00114 { 00115 VectorXd g(GetRows()); 00116 Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues(); 00117 g(0) = std::pow(x(0),2) + x(1); 00118 return g; 00119 }; 00120 00121 // The only constraint in this set is an equality constraint to 1. 00122 // Constant values should always be put into GetBounds(), not GetValues(). 00123 // For inequality constraints (<,>), use Bounds(x, inf) or Bounds(-inf, x). 00124 VecBound GetBounds() const override 00125 { 00126 VecBound b(GetRows()); 00127 b.at(0) = Bounds(1.0, 1.0); 00128 return b; 00129 } 00130 00131 // This function provides the first derivative of the constraints. 00132 // In case this is too difficult to write, you can also tell the solvers to 00133 // approximate the derivatives by finite differences and not overwrite this 00134 // function, e.g. in ipopt.cc::use_jacobian_approximation_ = true 00135 void FillJacobianBlock (std::string var_set, Jacobian& jac_block) const override 00136 { 00137 // must fill only that submatrix of the overall Jacobian that relates 00138 // to this constraint and "var_set1". even if more constraints or variables 00139 // classes are added, this submatrix will always start at row 0 and column 0, 00140 // thereby being independent from the overall problem. 00141 if (var_set == "var_set1") { 00142 Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues(); 00143 00144 jac_block.coeffRef(0, 0) = 2.0*x(0); // derivative of first constraint w.r.t x0 00145 jac_block.coeffRef(0, 1) = 1.0; // derivative of first constraint w.r.t x1 00146 } 00147 } 00148 }; 00149 00150 00151 class ExCost: public CostTerm { 00152 public: 00153 ExCost() : ExCost("cost_term1") {} 00154 ExCost(const std::string& name) : CostTerm(name) {} 00155 00156 double GetCost() const override 00157 { 00158 Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues(); 00159 return -std::pow(x(1)-2,2); 00160 }; 00161 00162 void FillJacobianBlock (std::string var_set, Jacobian& jac) const override 00163 { 00164 if (var_set == "var_set1") { 00165 Vector2d x = GetVariables()->GetComponent("var_set1")->GetValues(); 00166 00167 jac.coeffRef(0, 0) = 0.0; // derivative of cost w.r.t x0 00168 jac.coeffRef(0, 1) = -2.0*(x(1)-2.0); // derivative of cost w.r.t x1 00169 } 00170 } 00171 }; 00172 00173 } // namespace opt 00174