29 using namespace gtsam;
46 2.0 * I_1x1, Z_1x1, 10.0));
60 double x1 = 5,
x2 = 7;
61 values.
insert(
X(1), x1 * I_1x1);
100 2.0 * I_1x1, Z_1x1, 0.0));
117 initialValues.
insert(
X(1), I_1x1);
118 initialValues.
insert(
X(2), I_1x1);
135 currentSolution.
insert(
X(1), Z_1x1);
136 currentSolution.
insert(
X(2), Z_1x1);
141 CHECK(!workingSet.at(0)->active());
142 CHECK(workingSet.at(1)->active());
143 CHECK(workingSet.at(2)->active());
144 CHECK(!workingSet.at(3)->active());
159 currentSolution.
insert(
X(1), Z_1x1);
160 currentSolution.
insert(
X(2), Z_1x1);
162 std::vector<VectorValues>
expected(4), expectedDuals(4);
165 expectedDuals[0].insert(1, (
Vector(1) << 3).finished());
166 expectedDuals[0].insert(2,
kZero);
170 expectedDuals[1].insert(3, (
Vector(1) << 1.5).finished());
205 initialValues.
insert(
X(1), Z_1x1);
206 initialValues.
insert(
X(2), Z_1x1);
220 -1.5 *
kOne, 10.0 * I_1x1, 2.0 *
kOne,
253 double error_expected = problem.
cost.
error(expected);
254 double error_actual = problem.
cost.
error(actual);
265 double error_actual = problem.
cost.
error(actual);
273 double error_actual = problem.
cost.
error(actual);
280 double error_actual = problem.
cost.
error(actual);
287 double error_actual = problem.
cost.
error(actual);
294 double error_actual = problem.
cost.
error(actual);
302 double error_actual = problem.
cost.
error(actual);
309 double error_actual = problem.
cost.
error(actual);
325 2.0 * I_1x1, 6 * I_1x1, 1000.0));
343 initialValues.
insert(
X(1), Z_1x1);
344 initialValues.
insert(
X(2), Z_1x1);
370 qp.
cost.
add(
X(2), I_1x1, 2.5 * I_1x1);
387 initialValues.
insert(
X(2), Z_1x1);
407 initialValues.
insert(
X(1), (
Vector(2) << 10.0, 100.0).finished());
418 qp.
cost.
add(
X(1), I_2x2, Vector::Zero(2));
426 initialValues.
insert(
X(1), (
Vector(2) << -10.0, 100.0).finished());
bool converged
True if the algorithm has converged to a solution.
Policy of ActiveSetSolver to solve Quadratic Programming Problems.
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Concept check for values that can be used in unit tests.
VectorValues values
current best values at each step
static int runAllTests(TestResult &result)
State iterate(const State &state) const
Iterate 1 step, return a new state with a new workingSet and values.
#define DOUBLES_EQUAL(expected, actual, threshold)
std::pair< VectorValues, VectorValues > optimize(const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
GaussianFactorGraph buildWorkingGraph(const InequalityFactorGraph &workingSet, const VectorValues &xk=VectorValues()) const
BiCGSTAB< SparseMatrix< double > > solver
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Vector kZero
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
#define CHECK_EXCEPTION(condition, exception_name)
InequalityFactorGraph identifyActiveConstraints(const InequalityFactorGraph &inequalities, const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
Identify active constraints based on initial values.
pair< QP, QP > testParser(QPSParser parser)
double error(const VectorValues &x) const
GaussianFactorGraph cost
Quadratic cost factors.
QP createTestNocedal06bookEx16_4()
void add(const GaussianFactor &factor)
int identifyLeavingConstraint(const InequalityFactorGraph &workingSet, const VectorValues &lambdas) const
Identifies active constraints that shouldn't be active anymore.
void add(Args &&...args)
Add a linear inequality, forwards arguments to LinearInequality.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
GaussianFactorGraph buildDualGraph(const InequalityFactorGraph &workingSet, const VectorValues &delta) const
Just for testing...
#define LONGS_EQUAL(expected, actual)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
InequalityFactorGraph inequalities
linear inequality constraints: cI(x) <= 0
QP createTestMatlabQPEx()
void add(Args &&...args)
Add a linear inequality, forwards arguments to LinearInequality.
EqualityFactorGraph equalities
linear equality constraints: cE(x) = 0
This struct contains the state information for a single iteration.
A Gaussian factor using the canonical parameters (information form)
QP createEqualityConstrainedTest()
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
ActiveSetSolver< QP, QPPolicy, QPInitSolver > QPSolver
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
static const Eigen::MatrixBase< Vector2 >::ConstantReturnType Z_2x1
std::uint64_t Key
Integer nonlinear key type.