24 #include <boost/assign/std/vector.hpp> 25 #include <boost/assign/list_of.hpp> 28 using namespace gtsam;
36 const vector<pair<Key, Matrix> > terms = list_of < pair<Key, Matrix>
37 > (make_pair(5, Matrix3::Identity()))(
38 make_pair(10, 2 * Matrix3::Identity()))(
39 make_pair(15, 3 * Matrix3::Identity()));
56 boost::make_iterator_range(terms.begin(), terms.begin() + 1),
b, 0);
68 boost::make_iterator_range(terms.begin(), terms.begin() + 2),
b, 0);
70 terms[1].first, terms[1].second,
b, 0);
81 boost::make_iterator_range(terms.begin(), terms.begin() + 3),
b, 0);
83 terms[1].first, terms[1].second, terms[2].first, terms[2].second,
b, 0);
96 1.57, 2.695, -1.1, -2.35,
97 2.695, 11.3125, -0.65, -10.225,
99 -2.35, -10.225, 0.5, 9.25).finished(),
100 (
Vector(4) << -7.885, -28.5175, 2.75, 25.675).finished(),
107 catch (
const std::runtime_error& exception) {
118 values.
insert(5, Vector::Constant(3, 1.0));
119 values.
insert(10, Vector::Constant(3, 0.5));
120 values.
insert(15, Vector::Constant(3, 1.0/3.0));
122 Vector expected_unwhitened(3); expected_unwhitened << 2.0, 1.0, 0.0;
127 Vector expected_whitened(3); expected_whitened = expected_unwhitened;
131 double expected_error = 0.0;
132 double actual_error = factor.
error(values);
143 AExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
145 Matrix augmentedJacobianExpected(3, 10);
146 augmentedJacobianExpected << AExpected, rhsExpected;
165 Matrix jacobianExpected(3, 9);
166 jacobianExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
168 Matrix augmentedJacobianExpected(3, 10);
169 augmentedJacobianExpected << jacobianExpected, rhsExpected;
171 Matrix augmentedHessianExpected =
172 augmentedJacobianExpected.transpose() * simple::noise->R().transpose()
173 * simple::noise->R() * augmentedJacobianExpected;
204 expectedX.
insert(1, (
Vector(2) << -20.,-40.).finished());
205 expectedX.
insert(2, (
Vector(2) << 20., 40.).finished());
213 expectedG.
insert(1, (
Vector(2) << 0.2, -0.1).finished());
214 expectedG.
insert(2, (
Vector(2) << -0.2, 0.1).finished());
Provides additional testing facilities for common data structures.
Vector unweighted_error(const VectorValues &c) const
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
static int runAllTests(TestResult &result)
#define DOUBLES_EQUAL(expected, actual, threshold)
double error(const VectorValues &c) const override
const_iterator end() const
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
LinearEquality derived from Base with constrained noise model.
constexpr int first(int i)
Implementation details for constexpr functions.
const constBVector getb() const
#define EXPECT(condition)
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.)
Matrix augmentedJacobian() const override
bool empty() const override
constABlock getA(const_iterator variable) const
Vector error_vector(const VectorValues &c) const
const SharedDiagonal & get_model() const
#define LONGS_EQUAL(expected, actual)
noiseModel::Diagonal::shared_ptr SharedDiagonal
TEST(LinearEquality, constructors_and_accessors)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Matrix augmentedJacobianUnweighted() const
const KeyVector & keys() const
Access the factor's involved variable keys.
A Gaussian factor using the canonical parameters (information form)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
VectorValues gradientAtZero() const override
A'*b for Jacobian.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
#define GTSAM_CONCEPT_TESTABLE_INST(T)