25 using namespace gtsam;
32 using Terms = vector<pair<Key, Matrix> >;
33 const Terms terms{make_pair(5, I_3x3), make_pair(10, 2 * I_3x3),
34 make_pair(15, 3 * I_3x3)};
61 LinearEquality actual(terms[0].first, terms[0].second, terms[1].first,
62 terms[1].second,
b, 0);
73 LinearEquality actual(terms[0].first, terms[0].second, terms[1].first,
74 terms[1].second, terms[2].first, terms[2].second,
b,
89 (
Matrix(4, 4) << 1.57, 2.695, -1.1, -2.35, 2.695, 11.3125, -0.65, -10.225,
90 -1.1, -0.65, 1, 0.5, -2.35, -10.225, 0.5, 9.25)
92 (
Vector(4) << -7.885, -28.5175, 2.75, 25.675).finished(), 73.1725);
97 }
catch (
const std::runtime_error& exception) {
107 values.
insert(5, Vector::Constant(3, 1.0));
108 values.
insert(10, Vector::Constant(3, 0.5));
109 values.
insert(15, Vector::Constant(3, 1.0 / 3.0));
111 Vector expected_unwhitened(3);
112 expected_unwhitened << 2.0, 1.0, 0.0;
117 Vector expected_whitened(3);
118 expected_whitened = expected_unwhitened;
122 double expected_error = 0.0;
123 double actual_error = factor.
error(values);
133 AExpected << simple::terms[0].second, simple::terms[1].second,
134 simple::terms[2].second;
136 Matrix augmentedJacobianExpected(3, 10);
137 augmentedJacobianExpected << AExpected, rhsExpected;
156 Matrix jacobianExpected(3, 9);
157 jacobianExpected << simple::terms[0].second, simple::terms[1].second,
158 simple::terms[2].second;
160 Matrix augmentedJacobianExpected(3, 10);
161 augmentedJacobianExpected << jacobianExpected, rhsExpected;
163 Matrix augmentedHessianExpected =
164 augmentedJacobianExpected.transpose() * simple::noise->R().transpose() *
165 simple::noise->R() * augmentedJacobianExpected;
196 expectedX.
insert(1, (
Vector(2) << -20., -40.).finished());
197 expectedX.
insert(2, (
Vector(2) << 20., 40.).finished());
205 expectedG.
insert(1, (
Vector(2) << 0.2, -0.1).finished());
206 expectedG.
insert(2, (
Vector(2) << -0.2, 0.1).finished());
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
bool empty() const
Whether the factor is empty (involves zero variables).
Provides additional testing facilities for common data structures.
static int runAllTests(TestResult &result)
#define DOUBLES_EQUAL(expected, actual, threshold)
double error(const VectorValues &c) const override
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
iterator insert(const std::pair< Key, Vector > &key_value)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
LinearEquality derived from Base with constrained noise model.
Matrix augmentedJacobian() const override
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
Vector unweighted_error(const VectorValues &c) const
const_iterator end() const
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
Vector error_vector(const VectorValues &c) const
#define EXPECT(condition)
const constBVector getb() const
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Contains the HessianFactor class, a general quadratic factor.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define LONGS_EQUAL(expected, actual)
noiseModel::Diagonal::shared_ptr SharedDiagonal
TEST(LinearEquality, constructors_and_accessors)
VectorValues gradientAtZero() const override
A'*b for Jacobian.
Matrix augmentedJacobianUnweighted() const
A Gaussian factor using the canonical parameters (information form)
const KeyVector & keys() const
Access the factor's involved variable keys.
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const SharedDiagonal & get_model() const
#define GTSAM_CONCEPT_TESTABLE_INST(T)
constABlock getA(const_iterator variable) const