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


ifopt_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 21 2018 03:01:48