testLPSolver.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
21 
22 #include <gtsam/base/Testable.h>
24 #include <gtsam/inference/Symbol.h>
30 
32 
33 #include <boost/foreach.hpp>
34 #include <boost/range/adaptor/map.hpp>
35 
36 using namespace std;
37 using namespace gtsam;
38 using namespace gtsam::symbol_shorthand;
39 
40 static const Vector kOne = Vector::Ones(1), kZero = Vector::Zero(1);
41 
42 /* ************************************************************************* */
51  LP lp;
52  lp.cost = LinearCost(1, Vector2(-1., -1.)); // min -x1-x2 (max x1+x2)
53  lp.inequalities.add(1, Vector2(-1, 0), 0, 1); // x1 >= 0
54  lp.inequalities.add(1, Vector2(0, -1), 0, 2); // x2 >= 0
55  lp.inequalities.add(1, Vector2(1, 2), 4, 3); // x1 + 2*x2 <= 4
56  lp.inequalities.add(1, Vector2(4, 2), 12, 4); // 4x1 + 2x2 <= 12
57  lp.inequalities.add(1, Vector2(-1, 1), 1, 5); // -x1 + x2 <= 1
58  return lp;
59 }
60 
61 /* ************************************************************************* */
62 namespace gtsam {
63 
64 TEST(LPInitSolver, InfiniteLoopSingleVar) {
65  LP lp;
66  lp.cost = LinearCost(1, Vector3(0, 0, 1)); // min alpha
67  lp.inequalities.add(1, Vector3(-2, -1, -1), -2, 1); //-2x-y-a <= -2
68  lp.inequalities.add(1, Vector3(-1, 2, -1), 6, 2); // -x+2y-a <= 6
69  lp.inequalities.add(1, Vector3(-1, 0, -1), 0, 3); // -x - a <= 0
70  lp.inequalities.add(1, Vector3(1, 0, -1), 20, 4); // x - a <= 20
71  lp.inequalities.add(1, Vector3(0, -1, -1), 0, 5); // -y - a <= 0
72  LPSolver solver(lp);
73  VectorValues starter;
74  starter.insert(1, Vector3(0, 0, 2));
75  VectorValues results, duals;
76  boost::tie(results, duals) = solver.optimize(starter);
78  expected.insert(1, Vector3(13.5, 6.5, -6.5));
79  CHECK(assert_equal(results, expected, 1e-7));
80 }
81 
82 TEST(LPInitSolver, InfiniteLoopMultiVar) {
83  LP lp;
84  Key X = symbol('X', 1);
85  Key Y = symbol('Y', 1);
86  Key Z = symbol('Z', 1);
87  lp.cost = LinearCost(Z, kOne); // min alpha
88  lp.inequalities.add(X, -2.0 * kOne, Y, -1.0 * kOne, Z, -1.0 * kOne, -2,
89  1); //-2x-y-alpha <= -2
90  lp.inequalities.add(X, -1.0 * kOne, Y, 2.0 * kOne, Z, -1.0 * kOne, 6,
91  2); // -x+2y-alpha <= 6
92  lp.inequalities.add(X, -1.0 * kOne, Z, -1.0 * kOne, 0,
93  3); // -x - alpha <= 0
94  lp.inequalities.add(X, 1.0 * kOne, Z, -1.0 * kOne, 20,
95  4); // x - alpha <= 20
96  lp.inequalities.add(Y, -1.0 * kOne, Z, -1.0 * kOne, 0,
97  5); // -y - alpha <= 0
98  LPSolver solver(lp);
99  VectorValues starter;
100  starter.insert(X, kZero);
101  starter.insert(Y, kZero);
102  starter.insert(Z, Vector::Constant(1, 2.0));
103  VectorValues results, duals;
104  boost::tie(results, duals) = solver.optimize(starter);
106  expected.insert(X, Vector::Constant(1, 13.5));
107  expected.insert(Y, Vector::Constant(1, 6.5));
108  expected.insert(Z, Vector::Constant(1, -6.5));
109  CHECK(assert_equal(results, expected, 1e-7));
110 }
111 
112 TEST(LPInitSolver, Initialization) {
113  LP lp = simpleLP1();
114  LPInitSolver initSolver(lp);
115 
116  GaussianFactorGraph::shared_ptr initOfInitGraph =
117  initSolver.buildInitOfInitGraph();
118  VectorValues x0 = initOfInitGraph->optimize();
119  VectorValues expected_x0;
120  expected_x0.insert(1, Vector::Zero(2));
121  CHECK(assert_equal(expected_x0, x0, 1e-10));
122 
123  double y0 = initSolver.compute_y0(x0);
124  double expected_y0 = 0.0;
125  DOUBLES_EQUAL(expected_y0, y0, 1e-7);
126 
127  Key yKey = 2;
128  LP::shared_ptr initLP = initSolver.buildInitialLP(yKey);
129  LP expectedInitLP;
130  expectedInitLP.cost = LinearCost(yKey, kOne);
131  expectedInitLP.inequalities.add(1, Vector2(-1, 0), 2, Vector::Constant(1, -1),
132  0, 1); // -x1 - y <= 0
133  expectedInitLP.inequalities.add(1, Vector2(0, -1), 2, Vector::Constant(1, -1),
134  0, 2); // -x2 - y <= 0
135  expectedInitLP.inequalities.add(1, Vector2(1, 2), 2, Vector::Constant(1, -1),
136  4,
137  3); // x1 + 2*x2 - y <= 4
138  expectedInitLP.inequalities.add(1, Vector2(4, 2), 2, Vector::Constant(1, -1),
139  12,
140  4); // 4x1 + 2x2 - y <= 12
141  expectedInitLP.inequalities.add(1, Vector2(-1, 1), 2, Vector::Constant(1, -1),
142  1,
143  5); // -x1 + x2 - y <= 1
144  CHECK(assert_equal(expectedInitLP, *initLP, 1e-10));
145  LPSolver lpSolveInit(*initLP);
146  VectorValues xy0(x0);
147  xy0.insert(yKey, Vector::Constant(1, y0));
148  VectorValues xyInit = lpSolveInit.optimize(xy0).first;
149  VectorValues expected_init;
150  expected_init.insert(1, Vector::Ones(2));
151  expected_init.insert(2, Vector::Constant(1, -1));
152  CHECK(assert_equal(expected_init, xyInit, 1e-10));
153 
154  VectorValues x = initSolver.solve();
155  CHECK(lp.isFeasible(x));
156 }
157 } // namespace gtsam
158 
159 /* ************************************************************************* */
166 TEST(LPSolver, OverConstrainedLinearSystem) {
168  Matrix A1 = Vector3(1, 1, 1);
169  Matrix A2 = Vector3(1, -1, 2);
170  Vector b = Vector3(1, 5, 6);
171  graph.add(1, A1, 2, A2, b, noiseModel::Constrained::All(3));
172 
173  VectorValues x = graph.optimize();
174  // This check confirms that gtsam linear constraint solver can't handle
175  // over-constrained system
176  CHECK(graph[0]->error(x) != 0.0);
177 }
178 
179 TEST(LPSolver, overConstrainedLinearSystem2) {
181  graph.add(1, I_1x1, 2, I_1x1, kOne, noiseModel::Constrained::All(1));
182  graph.add(1, I_1x1, 2, -I_1x1, 5 * kOne, noiseModel::Constrained::All(1));
183  graph.add(1, I_1x1, 2, 2 * I_1x1, 6 * kOne, noiseModel::Constrained::All(1));
184  VectorValues x = graph.optimize();
185  // This check confirms that gtsam linear constraint solver can't handle
186  // over-constrained system
187  CHECK(graph.error(x) != 0.0);
188 }
189 
190 /* ************************************************************************* */
191 TEST(LPSolver, SimpleTest1) {
192  LP lp = simpleLP1();
193  LPSolver lpSolver(lp);
195  init.insert(1, Vector::Zero(2));
196 
197  VectorValues x1 =
199  VectorValues expected_x1;
200  expected_x1.insert(1, Vector::Ones(2));
201  CHECK(assert_equal(expected_x1, x1, 1e-10));
202 
203  VectorValues result, duals;
204  boost::tie(result, duals) = lpSolver.optimize(init);
205  VectorValues expectedResult;
206  expectedResult.insert(1, Vector2(8. / 3., 2. / 3.));
207  CHECK(assert_equal(expectedResult, result, 1e-10));
208 }
209 
210 /* ************************************************************************* */
211 TEST(LPSolver, TestWithoutInitialValues) {
212  LP lp = simpleLP1();
213  LPSolver lpSolver(lp);
214  VectorValues result, duals, expectedResult;
215  expectedResult.insert(1, Vector2(8. / 3., 2. / 3.));
216  boost::tie(result, duals) = lpSolver.optimize();
217  CHECK(assert_equal(expectedResult, result));
218 }
219 
226 /* ************************************************************************* */
228  LinearCost cost(1, Vector3(2., 4., 6.));
229  VectorValues x;
230  x.insert(1, Vector3(1., 3., 5.));
231  double error = cost.error(x);
232  double expectedError = 44.0;
233  DOUBLES_EQUAL(expectedError, error, 1e-100);
234 }
235 
236 /* ************************************************************************* */
237 int main() {
238  TestResult tr;
239  return TestRegistry::runAllTests(tr);
240 }
241 /* ************************************************************************* */
TEST(LPSolver, OverConstrainedLinearSystem)
#define CHECK(condition)
Definition: Test.h:109
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Scalar * b
Definition: benchVecAdd.cpp:17
Concept check for values that can be used in unit tests.
InequalityFactorGraph inequalities
Linear inequality constraints: cI(x) <= 0.
Definition: LP.h:56
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
double compute_y0(const VectorValues &x0) const
y = max_j ( Cj*x0 - dj ) – due to the inequality constraints y >= Cx - d
Matrix expected
Definition: testMatrix.cpp:974
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
LP simpleLP1()
std::pair< VectorValues, VectorValues > optimize(const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
bool isFeasible(const VectorValues &x) const
check feasibility
Definition: LP.h:62
Exception thrown when given Infeasible Initial Values.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
GaussianFactorGraph buildWorkingGraph(const InequalityFactorGraph &workingSet, const VectorValues &xk=VectorValues()) const
BiCGSTAB< SparseMatrix< double > > solver
Factor graph of all LinearInequality factors.
LP::shared_ptr buildInitialLP(Key yKey) const
build initial LP
NonlinearFactorGraph graph
GaussianFactorGraph::shared_ptr buildInitOfInitGraph() const
Factor graph of all LinearEquality factors.
double error(const VectorValues &x) const
double error(const VectorValues &c) const override
Definition: LinearCost.h:113
#define Z
Definition: icosphere.cpp:21
Factor Graph Values.
Definition: LP.h:51
void add(const GaussianFactor &factor)
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
LinearCost cost
Linear cost factor.
Definition: LP.h:54
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< LP > shared_ptr
Definition: LP.h:52
Linear Factor Graph where all factors are Gaussians.
Key symbol(unsigned char c, std::uint64_t j)
static Symbol x0('x', 0)
traits
Definition: chartTesting.h:28
static const Vector kZero
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Eigen::Vector2d Vector2
Definition: Vector.h:42
void add(Args &&...args)
Add a linear inequality, forwards arguments to LinearInequality.
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
Pose3 x1
Definition: testPose3.cpp:588
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1460
static const Vector kOne
int main()
static double error
Definition: testRot3.cpp:39
Policy of ActiveSetSolver to solve Linear Programming Problems.
VectorValues solve() const
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
iterator insert(const std::pair< Key, Vector > &key_value)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
This finds a feasible solution for an LP problem.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:59