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 <ifopt/problem.h> 00031 00032 00033 namespace ifopt { 00034 00035 Problem::Problem () 00036 :constraints_("constraints", false), 00037 costs_("costs", true) 00038 { 00039 variables_ = std::make_shared<Composite>("variables", false); 00040 } 00041 00042 void 00043 Problem::AddVariableSet(VariableSet::Ptr variable_set) 00044 { 00045 variables_->AddComponent(variable_set); 00046 } 00047 00048 void 00049 Problem::AddConstraintSet(ConstraintSet::Ptr constraint_set) 00050 { 00051 constraint_set->LinkWithVariables(variables_); 00052 constraints_.AddComponent(constraint_set); 00053 } 00054 00055 void 00056 Problem::AddCostSet(CostTerm::Ptr cost_set) 00057 { 00058 cost_set->LinkWithVariables(variables_); 00059 costs_.AddComponent(cost_set); 00060 } 00061 00062 int 00063 Problem::GetNumberOfOptimizationVariables () const 00064 { 00065 return variables_->GetRows(); 00066 } 00067 00068 Problem::VecBound 00069 Problem::GetBoundsOnOptimizationVariables () const 00070 { 00071 return variables_->GetBounds(); 00072 } 00073 00074 Problem::VectorXd 00075 Problem::GetVariableValues () const 00076 { 00077 return variables_->GetValues(); 00078 } 00079 00080 void 00081 Problem::SetVariables (const double* x) 00082 { 00083 variables_->SetVariables(ConvertToEigen(x)); 00084 } 00085 00086 double 00087 Problem::EvaluateCostFunction (const double* x) 00088 { 00089 VectorXd g = VectorXd::Zero(1); 00090 if (HasCostTerms()) { 00091 SetVariables(x); 00092 g = costs_.GetValues(); 00093 } 00094 return g(0); 00095 } 00096 00097 Problem::VectorXd 00098 Problem::EvaluateCostFunctionGradient (const double* x) 00099 { 00100 Jacobian jac = Jacobian(1,GetNumberOfOptimizationVariables()); 00101 if (HasCostTerms()) { 00102 SetVariables(x); 00103 jac = costs_.GetJacobian(); 00104 } 00105 00106 return jac.row(0).transpose(); 00107 } 00108 00109 Problem::VecBound 00110 Problem::GetBoundsOnConstraints () const 00111 { 00112 return constraints_.GetBounds(); 00113 } 00114 00115 int 00116 Problem::GetNumberOfConstraints () const 00117 { 00118 return GetBoundsOnConstraints().size(); 00119 } 00120 00121 Problem::VectorXd 00122 Problem::EvaluateConstraints (const double* x) 00123 { 00124 SetVariables(x); 00125 return constraints_.GetValues(); 00126 } 00127 00128 bool 00129 Problem::HasCostTerms () const 00130 { 00131 return costs_.GetRows()>0; 00132 } 00133 00134 void 00135 Problem::EvalNonzerosOfJacobian (const double* x, double* values) 00136 { 00137 SetVariables(x); 00138 Jacobian jac = GetJacobianOfConstraints(); 00139 00140 jac.makeCompressed(); // so the valuePtr() is dense and accurate 00141 std::copy(jac.valuePtr(), jac.valuePtr() + jac.nonZeros(), values); 00142 } 00143 00144 Problem::Jacobian 00145 Problem::GetJacobianOfConstraints () const 00146 { 00147 return constraints_.GetJacobian(); 00148 } 00149 00150 void 00151 Problem::SaveCurrent() 00152 { 00153 x_prev.push_back(variables_->GetValues()); 00154 } 00155 00156 Composite::Ptr 00157 Problem::GetOptVariables () const 00158 { 00159 return variables_; 00160 } 00161 00162 void 00163 Problem::SetOptVariables (int iter) 00164 { 00165 variables_->SetVariables(x_prev.at(iter)); 00166 } 00167 00168 void 00169 Problem::SetOptVariablesFinal () 00170 { 00171 variables_->SetVariables(x_prev.at(GetIterationCount()-1)); 00172 } 00173 00174 void 00175 Problem::PrintCurrent() const 00176 { 00177 variables_->Print(); 00178 costs_.Print(); 00179 constraints_.Print(); 00180 }; 00181 00182 Problem::VectorXd 00183 Problem::ConvertToEigen(const double* x) const 00184 { 00185 return Eigen::Map<const VectorXd>(x,GetNumberOfOptimizationVariables()); 00186 } 00187 00188 } /* namespace opt */ 00189