Go to the documentation of this file.
33 using namespace gtsam;
41 static auto kUnit2 = noiseModel::Unit::Create(2);
59 double actual = fg.
error(cfg);
69 conditional =
result.first->front();
72 Matrix I = 15 * I_2x2, R11 =
I, S12 = -0.111111 *
I, S13 = -0.444444 *
I;
86 double sigma = 0.0894427;
115 Matrix I = 15 * I_2x2, R11 =
I, S12 = -0.111111 *
I, S13 = -0.444444 *
I;
121 L(1), (
Matrix(4, 2) << 6.87184, 0, 0, 6.87184, 0, 0, 0, 0).finished(),
123 (
Matrix(4, 2) << -5.25494, 0, 0, -5.25494, -7.27607, 0, 0, -7.27607)
125 (
Vector(4) << -1.21268, 1.73817, -0.727607, 1.45521).finished(),
126 noiseModel::Unit::Create(4));
138 double sigma = 0.0894427;
227 size_t size1 = fg1.
size();
228 size_t size2 = fg2.
size();
239 for (
size_t k = 0; k <
v.size(); k++) cout <<
v[k] <<
" ";
275 Matrix Ap = I_1x1, An = I_1x1 * -1;
289 (
Matrix(2, 2) << 0.707107, -0.353553, 0.0, 0.612372).finished();
291 (
Matrix(2, 2) << 0.707107, -0.353553, 0.0, -0.612372).finished();
351 X(1), I_3x3,
X(2), I_3x3,
Z_3x1, noise));
353 X(2), I_3x3,
X(3), I_3x3,
Z_3x1, noise));
355 X(3), I_3x3,
X(4), I_3x3,
Z_3x1, noise));
357 X(5), I_3x3,
X(6), I_3x3,
Z_3x1, noise));
411 double relElevation = 6;
416 -1., 0.0, 1.2246468
e-16,
418 -1.2246468
e-16, 0.0, -1.),
419 Point3(0.511832102, 8.42819594, 5.76841725)));
420 initValues.
insert(l32,
Point3(0.364081507, 6.89766221, -0.231582751) );
421 initValues.
insert(l41,
Point3(1.61051523, 6.7373052, -0.231582751) );
426 -1., 0.0, 1.2246468
e-16,
428 -1.2246468
e-16, 0.0, -1),
429 Point3(0.511832102, 8.42819594, 5.76841725)), priorModel);
441 for (
const auto& [
key, clique]: actBT.
nodes()) {
445 EXPECT(!conditional->get_model());
static int runAllTests(TestResult &result)
double error(const VectorValues &x)
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Linear Factor Graph where all factors are Gaussians.
Reprojection of a LANDMARK to a 2D point.
TEST(GaussianFactorGraph, equals)
GaussianFactorGraph createMultiConstraintGraph()
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
typedef and functions to augment Eigen's MatrixXd
const GaussianFactorGraph factors
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
Serializable factor induced by a range measurement.
VectorValues createMultiConstraintValues()
double f2(const Vector2 &x)
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
const Nodes & nodes() const
Chordal Bayes Net, the result of eliminating a factor graph.
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
static const double sigma
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
void print(vector< int > v)
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Some functions to compute numerical derivatives.
const HybridBayesNet bayesNet
GaussianFactorGraph createGaussianFactorGraph()
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminatePartialSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
GaussianFactorGraph createSimpleConstraintGraph()
#define DOUBLES_EQUAL(expected, actual, threshold)
void replace(size_t index, sharedFactor factor)
noiseModel::Diagonal::shared_ptr SharedDiagonal
const HybridGaussianFactorGraph & lfg
static SharedDiagonal model
noiseModel::Base::shared_ptr SharedNoiseModel
std::shared_ptr< Cal3_S2 > shared_ptr
static enum @1096 ordering
const gtsam::Symbol key('X', 0)
GaussianFactorGraph createSingleConstraintGraph()
double f3(double x1, double x2)
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
double error(const VectorValues &x) const
VectorValues createSimpleConstraintValues()
VectorValues createSingleConstraintValues()
void insert(Key j, const Value &val)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
Array< int, Dynamic, 1 > v
double f4(double x, double y, double z)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
The most common 5DOF 3D->2D calibration.
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
bool equals(const This &fg, double tol=1e-9) const
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< HessianFactor > > EliminateCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
VectorValues createZeroDelta()
bool hasConstraints(const GaussianFactorGraph &factors)
std::uint64_t Key
Integer nonlinear key type.
Create small example with two poses and one landmark.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
VectorValues createCorrectDelta()
#define LONGS_EQUAL(expected, actual)
Jet< T, N > sqrt(const Jet< T, N > &f)
Rot2 R(Rot2::fromAngle(0.1))
GaussianFactorGraph createSmoother(int T)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:28