problem.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 <ifopt/problem.h>
00031 #include <iostream>
00032 #include <iomanip>
00033 
00034 
00035 namespace ifopt {
00036 
00037 Problem::Problem ()
00038     :constraints_("constraint-sets", false),
00039      costs_("cost-terms", true)
00040 {
00041   variables_ = std::make_shared<Composite>("variable-sets", false);
00042 }
00043 
00044 void
00045 Problem::AddVariableSet(VariableSet::Ptr variable_set)
00046 {
00047   variables_->AddComponent(variable_set);
00048 }
00049 
00050 void
00051 Problem::AddConstraintSet(ConstraintSet::Ptr constraint_set)
00052 {
00053   constraint_set->LinkWithVariables(variables_);
00054   constraints_.AddComponent(constraint_set);
00055 }
00056 
00057 void
00058 Problem::AddCostSet(CostTerm::Ptr cost_set)
00059 {
00060   cost_set->LinkWithVariables(variables_);
00061   costs_.AddComponent(cost_set);
00062 }
00063 
00064 int
00065 Problem::GetNumberOfOptimizationVariables () const
00066 {
00067   return variables_->GetRows();
00068 }
00069 
00070 Problem::VecBound
00071 Problem::GetBoundsOnOptimizationVariables () const
00072 {
00073   return variables_->GetBounds();
00074 }
00075 
00076 Problem::VectorXd
00077 Problem::GetVariableValues () const
00078 {
00079   return variables_->GetValues();
00080 }
00081 
00082 void
00083 Problem::SetVariables (const double* x)
00084 {
00085   variables_->SetVariables(ConvertToEigen(x));
00086 }
00087 
00088 double
00089 Problem::EvaluateCostFunction (const double* x)
00090 {
00091   VectorXd g = VectorXd::Zero(1);
00092   if (HasCostTerms()) {
00093     SetVariables(x);
00094     g = costs_.GetValues();
00095   }
00096   return g(0);
00097 }
00098 
00099 Problem::VectorXd
00100 Problem::EvaluateCostFunctionGradient (const double* x)
00101 {
00102   Jacobian jac = Jacobian(1,GetNumberOfOptimizationVariables());
00103   if (HasCostTerms()) {
00104     SetVariables(x);
00105     jac = costs_.GetJacobian();
00106   }
00107 
00108   return jac.row(0).transpose();
00109 }
00110 
00111 Problem::VecBound
00112 Problem::GetBoundsOnConstraints () const
00113 {
00114   return constraints_.GetBounds();
00115 }
00116 
00117 int
00118 Problem::GetNumberOfConstraints () const
00119 {
00120   return GetBoundsOnConstraints().size();
00121 }
00122 
00123 Problem::VectorXd
00124 Problem::EvaluateConstraints (const double* x)
00125 {
00126   SetVariables(x);
00127   return constraints_.GetValues();
00128 }
00129 
00130 bool
00131 Problem::HasCostTerms () const
00132 {
00133   return costs_.GetRows()>0;
00134 }
00135 
00136 void
00137 Problem::EvalNonzerosOfJacobian (const double* x, double* values)
00138 {
00139   SetVariables(x);
00140   Jacobian jac = GetJacobianOfConstraints();
00141 
00142   jac.makeCompressed(); // so the valuePtr() is dense and accurate
00143   std::copy(jac.valuePtr(), jac.valuePtr() + jac.nonZeros(), values);
00144 }
00145 
00146 Problem::Jacobian
00147 Problem::GetJacobianOfConstraints () const
00148 {
00149   return constraints_.GetJacobian();
00150 }
00151 
00152 void
00153 Problem::SaveCurrent()
00154 {
00155   x_prev.push_back(variables_->GetValues());
00156 }
00157 
00158 Composite::Ptr
00159 Problem::GetOptVariables () const
00160 {
00161   return variables_;
00162 }
00163 
00164 void
00165 Problem::SetOptVariables (int iter)
00166 {
00167   variables_->SetVariables(x_prev.at(iter));
00168 }
00169 
00170 void
00171 Problem::SetOptVariablesFinal ()
00172 {
00173   variables_->SetVariables(x_prev.at(GetIterationCount()-1));
00174 }
00175 
00176 void
00177 Problem::PrintCurrent() const
00178 {
00179   using namespace std;
00180   cout << "\n"
00181        << "************************************************************\n"
00182        << "    IFOPT - Interface to Nonlinear Optimizers (v2.0)\n"
00183        << "                \u00a9 Alexander W. Winkler\n"
00184        << "           https://github.com/ethz-adrl/ifopt\n"
00185        << "************************************************************"
00186        << "\n"
00187        << "Legend:\n"
00188        << "c - number of variables, constraints or cost terms" << std::endl
00189        << "i - indices of this set in overall problem" << std::endl
00190        << "v - number of [violated variable- or constraint-bounds] or [cost term value]"
00191        << "\n\n"
00192        << std::right
00193        << std::setw(33) << ""
00194        << std::setw(5)  << "c  "
00195        << std::setw(16) << "i    "
00196        << std::setw(11) << "v "
00197        << std::left
00198        << "\n";
00199 
00200   variables_->PrintAll();
00201   constraints_.PrintAll();
00202   costs_.PrintAll();
00203 };
00204 
00205 Problem::VectorXd
00206 Problem::ConvertToEigen(const double* x) const
00207 {
00208   return Eigen::Map<const VectorXd>(x,GetNumberOfOptimizationVariables());
00209 }
00210 
00211 } /* namespace opt */
00212 


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