34 #include <boost/assign/std/list.hpp> 35 #include <boost/assign/std/set.hpp> 42 using namespace gtsam;
61 double actual1 = fg.
error(c1);
65 double actual2 = fg.
error(c2);
75 KeySet::const_iterator it = actual.begin();
86 Ordering actual = Ordering::Colamd(nlfg);
90 Ordering expectedConstrained; expectedConstrained +=
L(1),
X(1),
X(2);
92 constraints[
X(2)] = 1;
93 Ordering actualConstrained = Ordering::ColamdConstrained(nlfg, constraints);
125 for (
size_t i=0;
i<fg.
size(); ++
i)
133 map<Key,Key> rekey_mapping;
134 rekey_mapping.insert(make_pair(
L(1),
L(4)));
139 for (
size_t i=0;
i<init.
size(); ++
i)
187 ordering +=
L(1),
X(2),
X(1);
192 auto iterator = hessianFactor->begin();
194 const auto index = std::distance(hessianFactor->begin(),
iterator);
195 auto block = hessianFactor->info().diagonalBlock(index);
196 for (
int j = 0;
j < block.rows();
j++) {
207 TEST(testNonlinearFactorGraph, eliminate) {
218 auto prior = noiseModel::Isotropic::Sigma(3, 1);
223 auto model = noiseModel::Diagonal::Sigmas(
Vector3(0.01, 0.01, 0.3));
228 auto model_rho = noiseModel::Isotropic::Sigma(1, 0.01);
240 ordering += 11, 21, 12, 22;
241 auto bn = linearized->eliminateSequential(ordering);
253 auto model_double = noiseModel::Isotropic::Sigma(1, 1);
263 values.insert(k, 11.0);
278 values.insert(k,
pose);
284 values.insert(k, pose_incorrect);
298 std::vector<bool> visited;
299 visited.assign(fg.
size(),
false);
300 const auto testFilter =
304 visited.at(index)=
true;
309 for (
bool visit : visited)
EXPECT(visit==
true);
Values createNoisyValues()
NonlinearFactorGraph clone() const
Clone() performs a deep-copy of the graph, including all of the factors.
m m block(1, 0, 2, 2)<< 4
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
GaussianFactorGraph createGaussianFactorGraph()
Point2 prior(const Point2 &x)
Prior on a single pose.
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
static enum @843 ordering
#define DOUBLES_EQUAL(expected, actual, threshold)
Represents a diagonal matrix with its storage.
Values updateCholesky(const Values &values, const Dampen &dampen=nullptr) const
Values retract(const VectorValues &delta) const
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
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
const_iterator begin() const
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
void push_factor(Key key)
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
GenericMeasurement< Point2, Point2 > Measurement
#define EXPECT(condition)
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearFactorGraph createNonlinearFactorGraph(const SharedNoiseModel &noiseModel1=impl::kSigma0_1, const SharedNoiseModel &noiseModel2=impl::kSigma0_2)
const_iterator end() const
NonlinearFactorGraph rekey(const std::map< Key, Key > &rekey_mapping) const
double probPrime(const Values &values) const
#define LONGS_EQUAL(expected, actual)
noiseModel::Diagonal::shared_ptr SharedDiagonal
boost::shared_ptr< SymbolicFactorGraph > symbolic() const
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
graph addPrior(1, priorMean, priorNoise)
TEST(NonlinearFactorGraph, equals)
#define EXPECT_LONGS_EQUAL(expected, actual)
VectorValues optimizeDensely() const
Class between(const Class &g) const
Create small example with two poses and one landmark.
EIGEN_DEVICE_FUNC void setIdentity()
double error(const Values &values) const
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
iterator erase(iterator item)
std::uint64_t Key
Integer nonlinear key type.