problem_test.cc
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 #include <gtest/gtest.h>
00031 
00032 #include <ifopt/problem.h>
00033 #include <ifopt/test_vars_constr_cost.h>
00034 
00035 using namespace ifopt;
00036 
00037 TEST(Problem, GetNumberOfOptimizationVariables)
00038 {
00039   Problem nlp;
00040   nlp.AddVariableSet(std::make_shared<ExVariables>("var_set0"));
00041   nlp.AddVariableSet(std::make_shared<ExVariables>("var_set1"));
00042 
00043   EXPECT_EQ(2+2, nlp.GetNumberOfOptimizationVariables());
00044 }
00045 
00046 
00047 TEST(Problem, GetBoundsOnOptimizationVariables)
00048 {
00049   Problem nlp;
00050   nlp.AddVariableSet(std::make_shared<ExVariables>("var_set0"));
00051   nlp.AddVariableSet(std::make_shared<ExVariables>("var_set1"));
00052 
00053   auto bounds = nlp.GetBoundsOnOptimizationVariables();
00054   EXPECT_EQ(2+2, bounds.size());
00055 
00056   // var_set0
00057   EXPECT_DOUBLE_EQ(-1.0, bounds.at(0).lower_);
00058   EXPECT_DOUBLE_EQ(+1.0, bounds.at(0).upper_);
00059   EXPECT_DOUBLE_EQ(-inf, bounds.at(1).lower_);
00060   EXPECT_DOUBLE_EQ(+inf, bounds.at(1).upper_);
00061 
00062   // var_set1
00063   EXPECT_DOUBLE_EQ(-1.0, bounds.at(2).lower_);
00064   EXPECT_DOUBLE_EQ(+1.0, bounds.at(2).upper_);
00065   EXPECT_DOUBLE_EQ(-inf, bounds.at(3).lower_);
00066   EXPECT_DOUBLE_EQ(+inf, bounds.at(3).upper_);
00067 }
00068 
00069 
00070 TEST(Problem, GetVariableValues)
00071 {
00072   auto var_set0 = std::make_shared<ExVariables>("var_set0");
00073   var_set0->SetVariables(Eigen::Vector2d(0.1, 0.2));
00074 
00075   auto var_set1 = std::make_shared<ExVariables>("var_set1");
00076   var_set1->SetVariables(Eigen::Vector2d(0.3, 0.4));
00077 
00078   Problem nlp;
00079   nlp.AddVariableSet(var_set0);
00080   nlp.AddVariableSet(var_set1);
00081 
00082   Eigen::VectorXd x = nlp.GetVariableValues();
00083   EXPECT_EQ(0.1, x(0));
00084   EXPECT_EQ(0.2, x(1));
00085   EXPECT_EQ(0.3, x(2));
00086   EXPECT_EQ(0.4, x(3));
00087 }
00088 
00089 
00090 TEST(Problem, GetNumberOfConstraints)
00091 {
00092   Problem nlp;
00093   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint1"));
00094 
00095   // add same constraints again for testing.
00096   // notice how the Jacobian calculation inside ExConstraint-class remains the
00097   //same - the full Jacobian is stitched together accordingly.
00098   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint2"));
00099 
00100   EXPECT_EQ(1+1, nlp.GetNumberOfConstraints());
00101 }
00102 
00103 
00104 TEST(Problem, GetBoundsOnConstraints)
00105 {
00106   Problem nlp;
00107   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint1"));
00108   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint2"));
00109 
00110   auto bounds = nlp.GetBoundsOnConstraints();
00111   // since it's an equality contraint, upper and lower bound are equal
00112   EXPECT_DOUBLE_EQ(1.0, bounds.at(0).lower_);
00113   EXPECT_DOUBLE_EQ(1.0, bounds.at(0).upper_);
00114   EXPECT_DOUBLE_EQ(1.0, bounds.at(1).lower_);
00115   EXPECT_DOUBLE_EQ(1.0, bounds.at(1).upper_);
00116 }
00117 
00118 
00119 TEST(Problem, EvaluateConstraints)
00120 {
00121   Problem nlp;
00122   nlp.AddVariableSet(std::make_shared<ExVariables>());
00123   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint1"));
00124   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint2"));
00125 
00126   double x[2] = { 2.0, 3.0 };
00127   Eigen::VectorXd g = nlp.EvaluateConstraints(x);
00128   EXPECT_DOUBLE_EQ(2*2.0+3.0, g(0)); // constant -1 moved to bounds
00129   EXPECT_DOUBLE_EQ(2*2.0+3.0, g(1)); // constant -1 moved to bounds
00130 }
00131 
00132 
00133 TEST(Problem, GetJacobianOfConstraints)
00134 {
00135   Problem nlp;
00136   nlp.AddVariableSet(std::make_shared<ExVariables>());
00137   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint1"));
00138   nlp.AddConstraintSet(std::make_shared<ExConstraint>("constraint2"));
00139 
00140   double x[2] = { 2.0, 3.0 };
00141   nlp.SetVariables(x);
00142   auto jac = nlp.GetJacobianOfConstraints();
00143   EXPECT_EQ(nlp.GetNumberOfConstraints(), jac.rows());
00144   EXPECT_EQ(nlp.GetNumberOfOptimizationVariables(), jac.cols());
00145 
00146   EXPECT_DOUBLE_EQ(2*x[0], jac.coeffRef(0,0)); // constraint 1 w.r.t x0
00147   EXPECT_DOUBLE_EQ(1.0,    jac.coeffRef(0,1)); // constraint 1 w.r.t x1
00148   EXPECT_DOUBLE_EQ(2*x[0], jac.coeffRef(1,0)); // constraint 2 w.r.t x0
00149   EXPECT_DOUBLE_EQ(1.0,    jac.coeffRef(1,1)); // constraint 2 w.r.t x1
00150 }
00151 
00152 
00153 TEST(Problem, EvaluateCostFunction)
00154 {
00155   Problem nlp;
00156   nlp.AddVariableSet(std::make_shared<ExVariables>());
00157   nlp.AddCostSet(std::make_shared<ExCost>("cost_term1"));
00158   nlp.AddCostSet(std::make_shared<ExCost>("cost_term2"));
00159 
00160   EXPECT_TRUE(nlp.HasCostTerms());
00161 
00162   double x[2] = { 2.0, 3.0 };
00163   EXPECT_DOUBLE_EQ(2*(-std::pow(x[1]-2.0,2)), nlp.EvaluateCostFunction(x)); // constant -1 moved to bounds
00164 }
00165 
00166 
00167 TEST(Problem, HasCostTerms)
00168 {
00169   Problem nlp;
00170   EXPECT_FALSE(nlp.HasCostTerms());
00171 
00172   nlp.AddVariableSet(std::make_shared<ExVariables>());
00173   EXPECT_FALSE(nlp.HasCostTerms());
00174 
00175   nlp.AddConstraintSet(std::make_shared<ExConstraint>());
00176   EXPECT_FALSE(nlp.HasCostTerms());
00177 
00178   nlp.AddCostSet(std::make_shared<ExCost>());
00179   EXPECT_TRUE(nlp.HasCostTerms());
00180 }
00181 
00182 
00183 TEST(Problem, EvaluateCostFunctionGradient)
00184 {
00185   Problem nlp;
00186   nlp.AddVariableSet(std::make_shared<ExVariables>());
00187   nlp.AddCostSet(std::make_shared<ExCost>("cost_term1"));
00188   nlp.AddCostSet(std::make_shared<ExCost>("cost_term2"));
00189 
00190   double x[2] = { 2.0, 3.0 };
00191   Eigen::VectorXd grad = nlp.EvaluateCostFunctionGradient(x);
00192 
00193   EXPECT_EQ(nlp.GetNumberOfOptimizationVariables(), grad.rows());
00194   EXPECT_DOUBLE_EQ(0.0,             grad(0)); // cost1+cost2 w.r.t x0
00195   EXPECT_DOUBLE_EQ(2*(-2*(x[1]-2)), grad(1)); // cost1+cost2 w.r.t x1
00196 }
00197 
00198 


ifopt
Author(s): Alexander W. Winkler
autogenerated on Sat May 18 2019 02:43:08