35 using namespace gtsam;
40 static const double tol = 1
e-5;
44 0., 4.6904).finished();
46 using Dims = std::vector<Eigen::Index>;
53 5.0254, 5.5432).finished();
56 5.5737, 3.0153).finished();
59 -3.0153, -3.5635).finished();
64 vector<pair<Key, Matrix> > terms = {{1,
R}, {3, S1}, {5, S2}, {7, S3}};
104 A1(0,0) = 1 ;
A1(1,0) = 2;
105 A1(0,1) = 3 ;
A1(1,1) = 4;
108 A2(0,0) = 6 ; A2(1,0) = 0.2;
109 A2(0,1) = 8 ; A2(1,1) = 0.4;
112 R(0,0) = 0.1 ;
R(1,0) = 0.3;
113 R(0,1) = 0.0 ;
R(1,1) = 0.34;
120 expected(1, d, R, 2, A1, 10, A2, model),
121 actual(1, d, R, 2, A1, 10, A2, model);
129 static constexpr
double sigma = 3.0;
133 key, Vector1::Constant(5), I_1x1,
165 double integral = 0.0;
167 for (
double x = -5.0 * sigma;
x <= 5.0 *
sigma;
x += 0.1 *
sigma) {
171 integral += 0.1 * sigma * density;
198 double integral = 0.0;
200 for (
double x = -5.0 * sigma;
x <= 5.0 *
sigma;
x += 0.1 *
sigma) {
204 integral += 0.1 * sigma * density;
214 expectedX(0) = 20-3-11 ; expectedX(1) = 40-7-15;
230 Vector sx1(2); sx1 << 1.0, 1.0;
231 Vector sl1(2); sl1 << 1.0, 1.0;
248 1.0, 0.0, 2.0, 0.0, 3.0, 0.0, 0.1,
249 0.0, 1.0, 0.0, 2.0, 0.0, 3.0, 0.2,
250 0.0, 0.0, 3.0, 0.0, 4.0, 0.0, 0.3,
251 0.0, 0.0, 0.0, 3.0, 0.0, 4.0, 0.4;
263 {2, sx1}, {1, (
Vector(4) << -3.1, -3.4, -11.9, -13.2).finished()}};
270 actual.
insert(cg.solve(actual));
280 1.0, 0.0, 2.0, 0.0, 3.0, 0.0, 0.1,
281 0.0, 1.0, 0.0, 2.0, 0.0, 3.0, 0.2,
282 0.0, 0.0, 3.0, 0.0, 4.0, 0.0, 0.3,
283 0.0, 0.0, 0.0, 3.0, 0.0, 4.0, 0.4;
304 actual.
insert(cg.solve(actual));
316 Matrix R11 = (
Matrix(1, 1) << 1.0).finished(), S12 = (
Matrix(1, 1) << 1.0).finished();
332 {2, (
Vector(1) << 5.).finished()}},
333 y = {{1, (
Vector(1) << 2.).finished()},
334 {2, (
Vector(1) << 3.).finished()}};
355 Matrix IExpected = R.transpose() *
R;
389 Matrix A2 = (
Matrix(2, 2) << 5., 6., 7., 8.).finished();
391 const double sigma = 3;
398 double expected1 = 0.5 * e1.dot(e1);
404 double expected2 = 0.5 * e2.dot(e2);
408 for (
auto conditional : {conditional1, conditional2}) {
420 const double sigma = 0.01;
427 frontalValues.
insert(
X(0), x0);
428 auto actual1 = conditional.likelihood(frontalValues);
437 auto actual2 = conditional.likelihood(x0);
447 const double sigma = 0.01;
450 auto actual1 =
density.sample();
459 auto actual2 = conditional.sample(given);
464 std::mt19937_64
rng(4242);
465 auto actual3 = conditional.sample(given, &rng);
477 values.
insert(
X(0), Vector1::Zero());
478 double logProbability = stdGaussian.logProbability(values);
493 x.
insert(
X(0), Vector3::Zero());
494 Matrix3 Sigma = I_3x3 * sigma *
sigma;
498 conditional.logNormalizationConstant(), 1
e-9);
504 Matrix A2 = (
Matrix(2, 2) << 5., 6., 7., 8.).finished();
506 const double sigma = 3;
513 "GaussianConditional p(x0)\n" 517 " mean: 1 elements\n" 519 "isotropic dim=2 sigma=3\n";
526 std::string expected1 =
527 "GaussianConditional p(x0 | x1)\n" 530 " S[x1] = [ -1 -2 ]\n" 533 "isotropic dim=2 sigma=3\n";
539 std::string expected2 =
540 "GaussianConditional p(x0 | y0 y1)\n" 543 " S[y0] = [ -1 -2 ]\n" 545 " S[y1] = [ -5 -6 ]\n" 548 "isotropic dim=2 sigma=3\n";
Provides additional testing facilities for common data structures.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
static int runAllTests(TestResult &result)
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
noiseModel::Diagonal::shared_ptr model
FACTOR::const_iterator endFrontals() const
static bool CheckInvariants(const GaussianConditional &conditional, const VALUES &x)
void determinant(const MatrixType &m)
A matrix with column blocks of pre-defined sizes. Used in JacobianFactor and GaussianConditional.
std::vector< Eigen::Index > Dims
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
VectorValues solve(const VectorValues &parents) const
FACTOR::const_iterator beginParents() const
const Matrix & matrix() const
Matrix information() const override
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
iterator insert(const std::pair< Key, Vector > &key_value)
const constBVector d() const
EIGEN_DEVICE_FUNC const LogReturnType log() const
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Point3 mean(const CONTAINER &points)
mean
FACTOR::const_iterator beginFrontals() const
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
static const VectorValues vv
FACTOR::const_iterator endParents() const
static GaussianDensity FromMeanAndStddev(Key key, const Vector &mean, double sigma)
Construct using a mean and standard deviation.
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues backSubstituteTranspose(const VectorValues &gx) const
Conditional Gaussian Base class.
static const auto unitPrior
static GaussianConditional FromMeanAndStddev(Key key, const Vector &mu, double sigma)
Construct from mean mu and standard deviation sigma.
Eigen::Matrix< double, 1, 1 > Vector1
static const auto widerPrior
static constexpr double sigma
noiseModel::Diagonal::shared_ptr SharedDiagonal
#define EXPECT_LONGS_EQUAL(expected, actual)
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Chordal Bayes Net, the result of eliminating a factor graph.
Jet< T, N > sqrt(const Jet< T, N > &f)
KeyVector::const_iterator const_iterator
Const iterator over keys.
TEST(SmartFactorBase, Pinhole)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
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
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
const SharedDiagonal & get_model() const
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)