33 #include <boost/foreach.hpp> 34 #include <boost/range/adaptor/map.hpp> 37 using namespace gtsam;
76 boost::tie(results, duals) = solver.
optimize(starter);
102 starter.
insert(Z, Vector::Constant(1, 2.0));
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));
120 expected_x0.
insert(1, Vector::Zero(2));
124 double expected_y0 = 0.0;
147 xy0.
insert(yKey, Vector::Constant(1, y0));
150 expected_init.
insert(1, Vector::Ones(2));
151 expected_init.
insert(2, Vector::Constant(1, -1));
171 graph.
add(1, A1, 2, A2, b, noiseModel::Constrained::All(3));
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));
195 init.
insert(1, Vector::Zero(2));
200 expected_x1.
insert(1, Vector::Ones(2));
204 boost::tie(result, duals) = lpSolver.
optimize(init);
216 boost::tie(result, duals) = lpSolver.
optimize();
232 double expectedError = 44.0;
TEST(LPSolver, OverConstrainedLinearSystem)
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Concept check for values that can be used in unit tests.
InequalityFactorGraph inequalities
Linear inequality constraints: cI(x) <= 0.
static int runAllTests(TestResult &result)
double compute_y0(const VectorValues &x0) const
y = max_j ( Cj*x0 - dj ) – due to the inequality constraints y >= Cx - d
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
#define DOUBLES_EQUAL(expected, actual, threshold)
std::pair< VectorValues, VectorValues > optimize(const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
bool isFeasible(const VectorValues &x) const
check feasibility
Exception thrown when given Infeasible Initial Values.
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
void add(const GaussianFactor &factor)
LinearCost cost
Linear cost factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::shared_ptr< LP > shared_ptr
Linear Factor Graph where all factors are Gaussians.
Key symbol(unsigned char c, std::uint64_t j)
static const Vector kZero
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
void add(Args &&...args)
Add a linear inequality, forwards arguments to LinearInequality.
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Policy of ActiveSetSolver to solve Linear Programming Problems.
VectorValues solve() const
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.
This finds a feasible solution for an LP problem.