composite.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/composite.h>
00031 
00032 #include <iostream>
00033 #include <iomanip>
00034 
00035 namespace ifopt {
00036 
00037 Component::Component (int num_rows, const std::string& name)
00038 {
00039   num_rows_ = num_rows;
00040   name_ = name;
00041 }
00042 
00043 int
00044 Component::GetRows () const
00045 {
00046   return num_rows_;
00047 }
00048 
00049 void
00050 Component::SetRows (int num_rows)
00051 {
00052   num_rows_ = num_rows;
00053 }
00054 
00055 std::string
00056 Component::GetName () const
00057 {
00058   return name_;
00059 }
00060 
00061 void Component::Print (double tol, int& index) const
00062 {
00063   // calculate squared bound violation
00064   VectorXd x = GetValues();
00065   VecBound bounds = GetBounds();
00066 
00067   std::vector<int> viol_idx;
00068   for (uint i=0; i<bounds.size(); ++i) {
00069     double lower = bounds.at(i).lower_;
00070     double upper = bounds.at(i).upper_;
00071     double val = x(i);
00072     if (val < lower-tol || upper+tol < val)
00073       viol_idx.push_back(i); // constraint out of bounds
00074   }
00075 
00076   std::string black = "\033[0m";
00077   std::string red   = "\033[31m";
00078   std::string color = viol_idx.empty()? black : red;
00079 
00080   std::cout.precision(2);
00081   std::cout << std::fixed
00082             << std::left
00083             << std::setw(30) << name_
00084             << std::right
00085             << std::setw(4) << num_rows_
00086             << std::setw(9) << index
00087             << std::setfill ('.')
00088             << std::setw(7) << index+num_rows_-1
00089             << std::setfill (' ')
00090             << color
00091             << std::setw(12) << viol_idx.size()
00092             << black
00093             << std::endl;
00094 
00095   index += num_rows_;
00096 }
00097 
00098 Composite::Composite (const std::string& name, bool is_cost) :Component(0, name)
00099 {
00100   is_cost_ = is_cost;
00101 }
00102 
00103 void
00104 Composite::AddComponent (const Component::Ptr& c)
00105 {
00106   // at this point the number of rows must be specified.
00107   assert(c->GetRows() != kSpecifyLater);
00108 
00109   components_.push_back(c);
00110 
00111   if (is_cost_)
00112     SetRows(1);
00113   else
00114     SetRows(GetRows()+ c->GetRows());
00115 }
00116 
00117 void
00118 Composite::ClearComponents ()
00119 {
00120   components_.clear();
00121   SetRows(0);
00122 }
00123 
00124 const Component::Ptr
00125 Composite::GetComponent (std::string name) const
00126 {
00127   for (const auto& c : components_)
00128     if (c->GetName() == name)
00129       return c;
00130 
00131   assert(false); // component with name doesn't exist, abort program
00132   return Component::Ptr();
00133 }
00134 
00135 Composite::VectorXd
00136 Composite::GetValues () const
00137 {
00138   VectorXd g_all = VectorXd::Zero(GetRows());
00139 
00140   int row = 0;
00141   for (const auto& c : components_) {
00142     int n_rows = c->GetRows();
00143     VectorXd g = c->GetValues();
00144     g_all.middleRows(row, n_rows) += g;
00145 
00146     if (!is_cost_)
00147       row += n_rows;
00148   }
00149   return g_all;
00150 }
00151 
00152 void
00153 Composite::SetVariables (const VectorXd& x)
00154 {
00155   int row = 0;
00156   for (auto& c : components_) {
00157     int n_rows = c->GetRows();
00158     c->SetVariables(x.middleRows(row,n_rows));
00159     row += n_rows;
00160   }
00161 }
00162 
00163 Composite::Jacobian
00164 Composite::GetJacobian () const
00165 {
00166   int n_var = components_.empty() ? 0 : components_.front()->GetJacobian().cols();
00167   Jacobian jacobian(GetRows(), n_var);
00168 
00169   if (n_var == 0) return jacobian;
00170 
00171   int row = 0;
00172   std::vector< Eigen::Triplet<double> > triplet_list;
00173 
00174   for (const auto& c : components_) {
00175     const Jacobian& jac = c->GetJacobian();
00176     triplet_list.reserve(triplet_list.size()+jac.nonZeros());
00177 
00178     for (int k=0; k<jac.outerSize(); ++k)
00179       for (Jacobian::InnerIterator it(jac,k); it; ++it)
00180         triplet_list.push_back(Eigen::Triplet<double>(row+it.row(), it.col(), it.value()));
00181 
00182     if (!is_cost_)
00183       row += c->GetRows();
00184   }
00185 
00186   jacobian.setFromTriplets(triplet_list.begin(), triplet_list.end());
00187   return jacobian;
00188 }
00189 
00190 Composite::VecBound
00191 Composite::GetBounds () const
00192 {
00193   VecBound bounds_;
00194   for (const auto& c : components_) {
00195     VecBound b = c->GetBounds();
00196     bounds_.insert(bounds_.end(), b.begin(), b.end());
00197   }
00198 
00199   return bounds_;
00200 }
00201 
00202 const Composite::ComponentVec
00203 Composite::GetComponents () const
00204 {
00205   return components_;
00206 }
00207 
00208 void
00209 Composite::PrintAll () const
00210 {
00211   int index = 0;
00212   double tol = 0.001; 
00213 
00214   std::cout << GetName() << ":\n";
00215   for (auto c : components_) {
00216     std::cout << "   "; // indent components
00217     c->Print(tol, index);
00218   }
00219   std::cout << std::endl;
00220 }
00221 
00222 } /* namespace opt */


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