composite_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 #include <ifopt/composite.h>
00032 
00033 
00034 namespace ifopt {
00035 
00036 class ExComponent : public Component {
00037 public:
00038   ExComponent(int n_var, const std::string& name) : Component(n_var, name) {};
00039 
00040   virtual VectorXd GetValues()   const { throw std::runtime_error("not implemented");};
00041   virtual VecBound GetBounds()   const { throw std::runtime_error("not implemented");};
00042   virtual Jacobian GetJacobian() const { throw std::runtime_error("not implemented");};
00043   virtual void SetVariables(const VectorXd& x) {};
00044 };
00045 
00046 } // namespace opt
00047 
00048 
00049 using namespace ifopt;
00050 
00051 TEST(Component, GetRows)
00052 {
00053   ExComponent c(2, "ex_component");
00054   EXPECT_EQ(2, c.GetRows());
00055 
00056   c.SetRows(4);
00057   EXPECT_EQ(4, c.GetRows());
00058 }
00059 
00060 
00061 TEST(Component, GetName)
00062 {
00063   ExComponent c(2, "ex_component");
00064   EXPECT_STREQ("ex_component", c.GetName().c_str());
00065 }
00066 
00067 
00068 TEST(Composite, GetRowsCost)
00069 {
00070   auto c1 = std::make_shared<ExComponent>(0, "component1");
00071   auto c2 = std::make_shared<ExComponent>(1, "component2");
00072   auto c3 = std::make_shared<ExComponent>(2, "component3");
00073 
00074   Composite cost("cost", true);
00075   cost.AddComponent(c1);
00076   cost.AddComponent(c2);
00077   cost.AddComponent(c3);
00078   EXPECT_EQ(1, cost.GetRows());
00079 }
00080 
00081 
00082 TEST(Composite, GetRowsConstraint)
00083 {
00084   auto c1 = std::make_shared<ExComponent>(0, "component1");
00085   auto c2 = std::make_shared<ExComponent>(1, "component2");
00086   auto c3 = std::make_shared<ExComponent>(2, "component3");
00087 
00088   Composite constraint("constraint", false);
00089   constraint.AddComponent(c1);
00090   constraint.AddComponent(c2);
00091   constraint.AddComponent(c3);
00092   EXPECT_EQ(0+1+2, constraint.GetRows());
00093 }
00094 
00095 
00096 TEST(Composite, GetComponent)
00097 {
00098   auto c1 = std::make_shared<ExComponent>(0, "component1");
00099   auto c2 = std::make_shared<ExComponent>(1, "component2");
00100   auto c3 = std::make_shared<ExComponent>(2, "component3");
00101 
00102   Composite comp("composite", false);
00103   comp.AddComponent(c1);
00104   comp.AddComponent(c2);
00105   comp.AddComponent(c3);
00106 
00107   auto c1_new = comp.GetComponent("component1");
00108   EXPECT_EQ(c1->GetRows(), c1_new->GetRows());
00109 
00110   auto c2_new = comp.GetComponent<ExComponent>("component2");
00111   EXPECT_EQ(c2->GetRows(), c2_new->GetRows());
00112 
00113   auto c3_new = comp.GetComponent<ExComponent>("component3");
00114   EXPECT_NE(c1->GetRows(), c3_new->GetRows());
00115 }
00116 
00117 
00118 TEST(Composite, ClearComponents)
00119 {
00120   auto c1 = std::make_shared<ExComponent>(0, "component1");
00121   auto c2 = std::make_shared<ExComponent>(1, "component2");
00122   auto c3 = std::make_shared<ExComponent>(2, "component3");
00123 
00124   Composite comp("composite", false);
00125   comp.AddComponent(c1);
00126   comp.AddComponent(c2);
00127   comp.AddComponent(c3);
00128 
00129   EXPECT_EQ(0+1+2, comp.GetRows());
00130 
00131   comp.ClearComponents();
00132   EXPECT_EQ(0, comp.GetRows());
00133 }


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