30 #include <gtest/gtest.h> 35 using namespace ifopt;
54 EXPECT_EQ(2+2, bounds.size());
57 EXPECT_DOUBLE_EQ(-1.0, bounds.at(0).lower_);
58 EXPECT_DOUBLE_EQ(+1.0, bounds.at(0).upper_);
59 EXPECT_DOUBLE_EQ(-
inf, bounds.at(1).lower_);
60 EXPECT_DOUBLE_EQ(+
inf, bounds.at(1).upper_);
63 EXPECT_DOUBLE_EQ(-1.0, bounds.at(2).lower_);
64 EXPECT_DOUBLE_EQ(+1.0, bounds.at(2).upper_);
65 EXPECT_DOUBLE_EQ(-
inf, bounds.at(3).lower_);
66 EXPECT_DOUBLE_EQ(+
inf, bounds.at(3).upper_);
72 auto var_set0 = std::make_shared<ExVariables>(
"var_set0");
73 var_set0->SetVariables(Eigen::Vector2d(0.1, 0.2));
75 auto var_set1 = std::make_shared<ExVariables>(
"var_set1");
76 var_set1->SetVariables(Eigen::Vector2d(0.3, 0.4));
112 EXPECT_DOUBLE_EQ(1.0, bounds.at(0).lower_);
113 EXPECT_DOUBLE_EQ(1.0, bounds.at(0).upper_);
114 EXPECT_DOUBLE_EQ(1.0, bounds.at(1).lower_);
115 EXPECT_DOUBLE_EQ(1.0, bounds.at(1).upper_);
126 double x[2] = { 2.0, 3.0 };
128 EXPECT_DOUBLE_EQ(2*2.0+3.0, g(0));
129 EXPECT_DOUBLE_EQ(2*2.0+3.0, g(1));
140 double x[2] = { 2.0, 3.0 };
146 EXPECT_DOUBLE_EQ(2*x[0], jac.coeffRef(0,0));
147 EXPECT_DOUBLE_EQ(1.0, jac.coeffRef(0,1));
148 EXPECT_DOUBLE_EQ(2*x[0], jac.coeffRef(1,0));
149 EXPECT_DOUBLE_EQ(1.0, jac.coeffRef(1,1));
157 nlp.
AddCostSet(std::make_shared<ExCost>(
"cost_term1"));
158 nlp.
AddCostSet(std::make_shared<ExCost>(
"cost_term2"));
162 double x[2] = { 2.0, 3.0 };
187 nlp.
AddCostSet(std::make_shared<ExCost>(
"cost_term1"));
188 nlp.
AddCostSet(std::make_shared<ExCost>(
"cost_term2"));
190 double x[2] = { 2.0, 3.0 };
194 EXPECT_DOUBLE_EQ(0.0, grad(0));
195 EXPECT_DOUBLE_EQ(2*(-2*(x[1]-2)), grad(1));
A generic optimization problem with variables, costs and constraints.
void AddCostSet(CostTerm::Ptr cost_set)
Add a cost term to the optimization problem.
VecBound GetBoundsOnConstraints() const
The upper and lower bound of each individual constraint.
double EvaluateCostFunction(const double *x)
The scalar cost for current optimization variables x.
VectorXd GetVariableValues() const
The current value of the optimization variables.
VectorXd EvaluateCostFunctionGradient(const double *x)
The column-vector of derivatives of the cost w.r.t. each variable.
bool HasCostTerms() const
True if the optimization problem includes a cost, false if merely a feasibility problem is defined...
VecBound GetBoundsOnOptimizationVariables() const
The maximum and minimum value each optimization variable is allowed to have.
void SetVariables(const double *x)
Updates the variables with the values of the raw pointer x.
Jacobian GetJacobianOfConstraints() const
The sparse-matrix representation of Jacobian of the constraints.
TEST(Problem, GetNumberOfOptimizationVariables)
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
Add a set of multiple constraints to the optimization problem.
int GetNumberOfConstraints() const
The number of individual constraints.
VectorXd EvaluateConstraints(const double *x)
Each constraint value g(x) for current optimization variables x.
void AddVariableSet(VariableSet::Ptr variable_set)
Add one individual set of variables to the optimization problem.
int GetNumberOfOptimizationVariables() const
The number of optimization variables.