Overview¶
QcqpProblem represents a quadratically constrained quadratic program over vector or matrix variables. It uses QpCost for quadratic objectives, LinearConstraint and QuadraticConstraint for scalar constraints, and the standard ConstrainedOptProblem interface for evaluation and optimization.
import gtsam
import numpy as npKey Concepts¶
QcqpProblemis a thinConstrainedOptProblemspecialized for QCQP costs plus linear and quadratic equality/inequality constraints.QpCost(keys, Q, columnDim)stores a row-space quadratic objective and linearizes exactly to aHessianFactor.The leading follows GTSAM’s factor-error convention. To represent a QCQP objective written without that factor, pass twice the row-space blocks.
QuadraticConstraintstores a scalar quadratic relation with equal, less-equal, or greater-equal sense.Variables are stored in
Valuesas directVectoror dynamicMatrixentries.
Mathematical Formulation¶
For vector variables, take . For matrix variables , row-space blocks , and per-variable constraint matrices , QcqpProblem represents:
Key C++ API¶
QcqpProblem(costs, equalityConstraints)orQcqpProblem(costs, equalityConstraints, inequalityConstraints)QcqpProblem::addConstraint(LinearConstraint)andQcqpProblem::addConstraint(QuadraticConstraint)QpCost(keys, Q, columnDim)for row-space quadratic objectives; omitcolumnDimfor vector variablesQuadraticConstraint::Equal(key, A, b),QuadraticConstraint::LessEqual(key, A, b), andQuadraticConstraint::GreaterEqual(key, A, b)inherited
ConstrainedOptProblemaccessors such ascosts(),eConstraints(), andevaluate(values)
Concise C++ Example¶
#include <gtsam/constrained/QuadraticConstraint.h>
#include <gtsam/constrained/QcqpProblem.h>
#include <gtsam/constrained/QpCost.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/Values.h>
using namespace gtsam;
Key x = Symbol('x', 0);
Matrix Q = Matrix::Identity(2, 2);
QcqpProblem problem;
problem.addCost(QpCost(KeyVector{x}, SymmetricBlockMatrix({2}, Q)));
problem.addConstraint(QuadraticConstraint::Equal(x, Matrix::Identity(2, 2), 1.0));
Values values;
values.insert(x, Vector2(1.0, 0.0));
auto [cost, eqViolation, ineqViolation] = problem.evaluate(values);Minimal Python Example¶
from gtsam.symbol_shorthand import X
x = X(0)
Q = np.eye(2)
problem = gtsam.QcqpProblem()
problem.addCost(gtsam.QpCost(gtsam.KeyVector([x]), gtsam.SymmetricBlockMatrix([2], Q)))
problem.addConstraint(gtsam.QuadraticConstraint.Equal(x, Q, 1.0))
values = gtsam.Values()
values.insert(x, np.array([1.0, 0.0]))
problem.evaluate(values)(0.5, 0.0, 0.0)Current Scope¶
QcqpProblemassembles quadratic costs plus linear and quadratic constraints.QpCostandQuadraticConstraintoperate on direct vector or matrix values already inserted intoValues.