Go to the documentation of this file.
   39 using namespace gtsam;
 
   72   KeySet::const_iterator it = actual.begin();
 
   83   Ordering actual = Ordering::Colamd(nlfg);
 
   87   const Ordering expectedConstrained{
L(1), 
X(1), 
X(2)};
 
   89   constraints[
X(2)] = 1;
 
   90   Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints);
 
  110                                          noiseModel::Isotropic::Sigma(1, 1.0));
 
  140   for (
size_t i=0; 
i<fg.
size(); ++
i)
 
  148   map<Key,Key> rekey_mapping;
 
  149   rekey_mapping.insert(make_pair(
L(1), 
L(4)));
 
  154   for (
size_t i=0; 
i<
init.size(); ++
i)
 
  206     auto iterator = hessianFactor->begin();
 
  209       auto block = hessianFactor->info().diagonalBlock(index);
 
  210       for (
int j = 0; 
j < 
block.rows(); 
j++) {
 
  221 TEST(testNonlinearFactorGraph, eliminate) {
 
  232   auto prior = noiseModel::Isotropic::Sigma(3, 1);
 
  237   auto model = noiseModel::Diagonal::Sigmas(
Vector3(0.01, 0.01, 0.3));
 
  242   auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01);
 
  254   auto bn = linearized->eliminateSequential(
ordering);
 
  266   auto model_double = noiseModel::Isotropic::Sigma(1, 1);
 
  312   std::vector<bool> visited;
 
  313   visited.assign(fg.
size(), 
false);
 
  314   const auto testFilter =
 
  318         visited.at(index)=
true;
 
  323   for (
bool visit : visited) 
EXPECT(visit==
true);
 
  332       "  var7782220156096217089[label=\"l1\"];\n" 
  333       "  var8646911284551352321[label=\"x1\"];\n" 
  334       "  var8646911284551352322[label=\"x2\"];\n" 
  336       "  factor0[label=\"\", shape=point];\n" 
  337       "  var8646911284551352321--factor0;\n" 
  338       "  factor1[label=\"\", shape=point];\n" 
  339       "  var8646911284551352321--factor1;\n" 
  340       "  var8646911284551352322--factor1;\n" 
  341       "  factor2[label=\"\", shape=point];\n" 
  342       "  var8646911284551352321--factor2;\n" 
  343       "  var7782220156096217089--factor2;\n" 
  344       "  factor3[label=\"\", shape=point];\n" 
  345       "  var8646911284551352322--factor3;\n" 
  346       "  var7782220156096217089--factor3;\n" 
  350   string actual = fg.
dot();
 
  360       "  var7782220156096217089[label=\"l1\", pos=\"0,0!\"];\n" 
  361       "  var8646911284551352321[label=\"x1\", pos=\"1,0!\"];\n" 
  362       "  var8646911284551352322[label=\"x2\", pos=\"1,1.5!\"];\n" 
  364       "  factor0[label=\"\", shape=point];\n" 
  365       "  var8646911284551352321--factor0;\n" 
  366       "  factor1[label=\"\", shape=point];\n" 
  367       "  var8646911284551352321--factor1;\n" 
  368       "  var8646911284551352322--factor1;\n" 
  369       "  factor2[label=\"\", shape=point];\n" 
  370       "  var8646911284551352321--factor2;\n" 
  371       "  var7782220156096217089--factor2;\n" 
  372       "  factor3[label=\"\", shape=point];\n" 
  373       "  var8646911284551352322--factor3;\n" 
  374       "  var7782220156096217089--factor3;\n" 
  
static int runAllTests(TestResult &result)
Class between(const Class &g) const
Values createNoisyValues()
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
Represents a diagonal matrix with its storage.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
VectorValues optimizeDensely() const
#define EXPECT_LONGS_EQUAL(expected, actual)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
TEST(NonlinearFactorGraph, equals)
typedef and functions to augment Eigen's MatrixXd
Serializable factor induced by a range measurement.
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
double probPrime(const Values &values) const
void dot(std::ostream &os, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const
Output to graphviz format, stream version, with Values/extra options.
m m block(1, 0, 2, 2)<< 4
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
This is the base class for all measurement types.
iterator erase(iterator item)
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
static std::stringstream ss
double error(const Values &values) const
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
GaussianFactorGraph createGaussianFactorGraph()
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
#define DOUBLES_EQUAL(expected, actual, threshold)
NonlinearFactorGraph clone() const
Clone() performs a deep-copy of the graph, including all of the factors.
noiseModel::Diagonal::shared_ptr SharedDiagonal
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
void insert(Key j, const Vector &value)
graph addPrior(1, Pose2(0, 0, 0), priorNoise)
noiseModel::Diagonal::shared_ptr model
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
static enum @1096 ordering
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
void printErrors(const Values &values, const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter, const std::function< bool(const Factor *, double, size_t)> &printCondition=[](const Factor *, double, size_t) {return true;}) const
Factor Graph consisting of non-linear factors.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
const_iterator end() const
Values updateCholesky(const Values &values, const Dampen &dampen=nullptr) const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
const_iterator begin() const
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Double_ distance(const OrientedPlane3_ &p)
std::shared_ptr< SymbolicFactorGraph > symbolic() const
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
Create small example with two poses and one landmark.
EIGEN_DEVICE_FUNC void setIdentity()
#define LONGS_EQUAL(expected, actual)
3D Pose manifold SO(3) x R^3 and group SE(3)
static constexpr double k
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:07:00