Merge pull request #42 from borglab/feature/iSAM2_refactor

iSAM2 refactor
release/4.3a0
Frank Dellaert 2019-06-03 22:05:37 -04:00 committed by GitHub
commit e9d2f8775f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 1017 additions and 1064 deletions

View File

@ -89,14 +89,14 @@ namespace gtsam {
/** Map from keys to Clique */
typedef ConcurrentMap<Key, sharedClique> Nodes;
/** Root cliques */
typedef FastVector<sharedClique> Roots;
protected:
/** Map from indices to Clique */
Nodes nodes_;
/** Root cliques */
typedef FastVector<sharedClique> Roots;
/** Root cliques */
Roots roots_;

View File

@ -98,7 +98,7 @@ namespace gtsam {
for (size_t j = 0; j < n; j++)
{
// Retrieve the factors involving this variable and create the current node
const VariableIndex::Factors& factors = structure[order[j]];
const FactorIndices& factors = structure[order[j]];
const sharedNode node = boost::make_shared<Node>();
node->key = order[j];

View File

@ -79,7 +79,7 @@ Ordering Ordering::ColamdConstrained(const VariableIndex& variableIndex,
size_t index = 0;
for (auto key_factors: variableIndex) {
// Arrange factor indices into COLAMD format
const VariableIndex::Factors& column = key_factors.second;
const FactorIndices& column = key_factors.second;
for(size_t factorIndex: column) {
A[count++] = (int) factorIndex; // copy sparse column
}

View File

@ -67,8 +67,8 @@ void VariableIndex::remove(ITERATOR firstFactor, ITERATOR lastFactor,
"Internal error, requested inconsistent number of factor indices and factors in VariableIndex::remove");
if (factors[i]) {
for(Key j: *factors[i]) {
Factors& factorEntries = internalAt(j);
Factors::iterator entry = std::find(factorEntries.begin(),
FactorIndices& factorEntries = internalAt(j);
auto entry = std::find(factorEntries.begin(),
factorEntries.end(), *factorIndex);
if (entry == factorEntries.end())
throw std::invalid_argument(

View File

@ -41,26 +41,22 @@ namespace gtsam {
* \nosubgrouping
*/
class GTSAM_EXPORT VariableIndex {
public:
public:
typedef boost::shared_ptr<VariableIndex> shared_ptr;
typedef FactorIndices Factors;
typedef Factors::iterator Factor_iterator;
typedef Factors::const_iterator Factor_const_iterator;
typedef FactorIndices::iterator Factor_iterator;
typedef FactorIndices::const_iterator Factor_const_iterator;
protected:
typedef FastMap<Key,Factors> KeyMap;
protected:
typedef FastMap<Key, FactorIndices> KeyMap;
KeyMap index_;
size_t nFactors_; // Number of factors in the original factor graph.
size_t nEntries_; // Sum of involved variable counts of each factor.
size_t nFactors_; // Number of factors in the original factor graph.
size_t nEntries_; // Sum of involved variable counts of each factor.
public:
public:
typedef KeyMap::const_iterator const_iterator;
typedef KeyMap::const_iterator iterator;
typedef KeyMap::value_type value_type;
public:
/// @name Standard Constructors
/// @{
@ -71,8 +67,10 @@ public:
* Create a VariableIndex that computes and stores the block column structure
* of a factor graph.
*/
template<class FG>
VariableIndex(const FG& factorGraph) : nFactors_(0), nEntries_(0) { augment(factorGraph); }
template <class FG>
explicit VariableIndex(const FG& factorGraph) : nFactors_(0), nEntries_(0) {
augment(factorGraph);
}
/// @}
/// @name Standard Interface
@ -88,7 +86,7 @@ public:
size_t nEntries() const { return nEntries_; }
/// Access a list of factors by variable
const Factors& operator[](Key variable) const {
const FactorIndices& operator[](Key variable) const {
KeyMap::const_iterator item = index_.find(variable);
if(item == index_.end())
throw std::invalid_argument("Requested non-existent variable from VariableIndex");
@ -96,6 +94,11 @@ public:
return item->second;
}
/// Return true if no factors associated with a variable
const bool empty(Key variable) const {
return (*this)[variable].empty();
}
/// @}
/// @name Testable
/// @{
@ -166,16 +169,18 @@ protected:
Factor_const_iterator factorsEnd(Key variable) const { return internalAt(variable).end(); }
/// Internal version of 'at' that asserts existence
const Factors& internalAt(Key variable) const {
const FactorIndices& internalAt(Key variable) const {
const KeyMap::const_iterator item = index_.find(variable);
assert(item != index_.end());
return item->second; }
return item->second;
}
/// Internal version of 'at' that asserts existence
Factors& internalAt(Key variable) {
FactorIndices& internalAt(Key variable) {
const KeyMap::iterator item = index_.find(variable);
assert(item != index_.end());
return item->second; }
return item->second;
}
/// @}
};

View File

@ -31,150 +31,6 @@ using namespace std;
namespace gtsam {
/* ************************************************************************* */
void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors,
bool useUnusedSlots,
NonlinearFactorGraph* nonlinearFactors,
FactorIndices* newFactorIndices) {
newFactorIndices->resize(newFactors.size());
if (useUnusedSlots) {
size_t globalFactorIndex = 0;
for (size_t newFactorIndex = 0; newFactorIndex < newFactors.size();
++newFactorIndex) {
// Loop to find the next available factor slot
do {
// If we need to add more factors than we have room for, resize
// nonlinearFactors, filling the new slots with NULL factors. Otherwise,
// check if the current factor in nonlinearFactors is already used, and
// if so, increase globalFactorIndex. If the current factor in
// nonlinearFactors is unused, break out of the loop and use the current
// slot.
if (globalFactorIndex >= nonlinearFactors->size())
nonlinearFactors->resize(nonlinearFactors->size() +
newFactors.size() - newFactorIndex);
else if ((*nonlinearFactors)[globalFactorIndex])
++globalFactorIndex;
else
break;
} while (true);
// Use the current slot, updating nonlinearFactors and newFactorSlots.
(*nonlinearFactors)[globalFactorIndex] = newFactors[newFactorIndex];
(*newFactorIndices)[newFactorIndex] = globalFactorIndex;
}
} else {
// We're not looking for unused slots, so just add the factors at the end.
for (size_t i = 0; i < newFactors.size(); ++i)
(*newFactorIndices)[i] = i + nonlinearFactors->size();
nonlinearFactors->push_back(newFactors);
}
}
/* ************************************************************************* */
KeySet ISAM2::Impl::CheckRelinearizationFull(
const VectorValues& delta,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
KeySet relinKeys;
if (const double* threshold = boost::get<double>(&relinearizeThreshold)) {
for (const VectorValues::KeyValuePair& key_delta : delta) {
double maxDelta = key_delta.second.lpNorm<Eigen::Infinity>();
if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
}
} else if (const FastMap<char, Vector>* thresholds =
boost::get<FastMap<char, Vector> >(&relinearizeThreshold)) {
for (const VectorValues::KeyValuePair& key_delta : delta) {
const Vector& threshold =
thresholds->find(Symbol(key_delta.first).chr())->second;
if (threshold.rows() != key_delta.second.rows())
throw std::invalid_argument(
"Relinearization threshold vector dimensionality for '" +
std::string(1, Symbol(key_delta.first).chr()) +
"' passed into iSAM2 parameters does not match actual variable "
"dimensionality.");
if ((key_delta.second.array().abs() > threshold.array()).any())
relinKeys.insert(key_delta.first);
}
}
return relinKeys;
}
/* ************************************************************************* */
static void CheckRelinearizationRecursiveDouble(
double threshold, const VectorValues& delta,
const ISAM2::sharedClique& clique, KeySet* relinKeys) {
// Check the current clique for relinearization
bool relinearize = false;
for (Key var : *clique->conditional()) {
double maxDelta = delta[var].lpNorm<Eigen::Infinity>();
if (maxDelta >= threshold) {
relinKeys->insert(var);
relinearize = true;
}
}
// If this node was relinearized, also check its children
if (relinearize) {
for (const ISAM2::sharedClique& child : clique->children) {
CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys);
}
}
}
/* ************************************************************************* */
static void CheckRelinearizationRecursiveMap(
const FastMap<char, Vector>& thresholds, const VectorValues& delta,
const ISAM2::sharedClique& clique, KeySet* relinKeys) {
// Check the current clique for relinearization
bool relinearize = false;
for (Key var : *clique->conditional()) {
// Find the threshold for this variable type
const Vector& threshold = thresholds.find(Symbol(var).chr())->second;
const Vector& deltaVar = delta[var];
// Verify the threshold vector matches the actual variable size
if (threshold.rows() != deltaVar.rows())
throw std::invalid_argument(
"Relinearization threshold vector dimensionality for '" +
std::string(1, Symbol(var).chr()) +
"' passed into iSAM2 parameters does not match actual variable "
"dimensionality.");
// Check for relinearization
if ((deltaVar.array().abs() > threshold.array()).any()) {
relinKeys->insert(var);
relinearize = true;
}
}
// If this node was relinearized, also check its children
if (relinearize) {
for (const ISAM2::sharedClique& child : clique->children) {
CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys);
}
}
}
/* ************************************************************************* */
KeySet ISAM2::Impl::CheckRelinearizationPartial(
const ISAM2::Roots& roots, const VectorValues& delta,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
KeySet relinKeys;
for (const ISAM2::sharedClique& root : roots) {
if (relinearizeThreshold.type() == typeid(double))
CheckRelinearizationRecursiveDouble(
boost::get<double>(relinearizeThreshold), delta, root, &relinKeys);
else if (relinearizeThreshold.type() == typeid(FastMap<char, Vector>))
CheckRelinearizationRecursiveMap(
boost::get<FastMap<char, Vector> >(relinearizeThreshold), delta, root,
&relinKeys);
}
return relinKeys;
}
/* ************************************************************************* */
namespace internal {
inline static void optimizeInPlace(const ISAM2::sharedClique& clique,
@ -189,7 +45,7 @@ inline static void optimizeInPlace(const ISAM2::sharedClique& clique,
} // namespace internal
/* ************************************************************************* */
size_t ISAM2::Impl::UpdateGaussNewtonDelta(const ISAM2::Roots& roots,
size_t DeltaImpl::UpdateGaussNewtonDelta(const ISAM2::Roots& roots,
const KeySet& replacedKeys,
double wildfireThreshold,
VectorValues* delta) {
@ -272,7 +128,7 @@ void updateRgProd(const ISAM2::sharedClique& clique, const KeySet& replacedKeys,
} // namespace internal
/* ************************************************************************* */
size_t ISAM2::Impl::UpdateRgProd(const ISAM2::Roots& roots,
size_t DeltaImpl::UpdateRgProd(const ISAM2::Roots& roots,
const KeySet& replacedKeys,
const VectorValues& gradAtZero,
VectorValues* RgProd) {
@ -287,7 +143,7 @@ size_t ISAM2::Impl::UpdateRgProd(const ISAM2::Roots& roots,
}
/* ************************************************************************* */
VectorValues ISAM2::Impl::ComputeGradientSearch(const VectorValues& gradAtZero,
VectorValues DeltaImpl::ComputeGradientSearch(const VectorValues& gradAtZero,
const VectorValues& RgProd) {
// Compute gradient squared-magnitude
const double gradientSqNorm = gradAtZero.dot(gradAtZero);

View File

@ -11,18 +11,65 @@
/**
* @file ISAM2-impl.h
* @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
* @author Michael Kaess, Richard Roberts
* @brief Incremental update functionality (ISAM2) for BayesTree, with fluid
* relinearization.
* @author Michael Kaess, Richard Roberts, Frank Dellaert
*/
#pragma once
#include <gtsam/linear/GaussianBayesTree.h>
#include <gtsam/nonlinear/ISAM2.h>
#include <gtsam/nonlinear/ISAM2Result.h>
#include <gtsam/base/debug.h>
#include <gtsam/inference/JunctionTree-inst.h> // We need the inst file because we'll make a special JT templated on ISAM2
#include <gtsam/inference/Symbol.h>
#include <gtsam/inference/VariableIndex.h>
#include <gtsam/linear/GaussianBayesTree.h>
#include <gtsam/linear/GaussianEliminationTree.h>
#include <boost/range/adaptors.hpp>
#include <boost/range/algorithm/copy.hpp>
namespace br {
using namespace boost::range;
using namespace boost::adaptors;
} // namespace br
#include <algorithm>
#include <limits>
#include <string>
#include <utility>
namespace gtsam {
struct GTSAM_EXPORT ISAM2::Impl {
/* ************************************************************************* */
// Special BayesTree class that uses ISAM2 cliques - this is the result of
// reeliminating ISAM2 subtrees.
class ISAM2BayesTree : public ISAM2::Base {
public:
typedef ISAM2::Base Base;
typedef ISAM2BayesTree This;
typedef boost::shared_ptr<This> shared_ptr;
ISAM2BayesTree() {}
};
/* ************************************************************************* */
// Special JunctionTree class that produces ISAM2 BayesTree cliques, used for
// reeliminating ISAM2 subtrees.
class ISAM2JunctionTree
: public JunctionTree<ISAM2BayesTree, GaussianFactorGraph> {
public:
typedef JunctionTree<ISAM2BayesTree, GaussianFactorGraph> Base;
typedef ISAM2JunctionTree This;
typedef boost::shared_ptr<This> shared_ptr;
explicit ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree)
: Base(eliminationTree) {}
};
/* ************************************************************************* */
struct GTSAM_EXPORT DeltaImpl {
struct GTSAM_EXPORT PartialSolveResult {
ISAM2::sharedClique bayesTree;
};
@ -34,57 +81,468 @@ struct GTSAM_EXPORT ISAM2::Impl {
boost::optional<FastMap<Key, int> > constrainedKeys;
};
/// Perform the first part of the bookkeeping updates for adding new factors. Adds them to the
/// complete list of nonlinear factors, and populates the list of new factor indices, both
/// optionally finding and reusing empty factor slots.
static void AddFactorsStep1(const NonlinearFactorGraph& newFactors, bool useUnusedSlots,
NonlinearFactorGraph* nonlinearFactors, FactorIndices* newFactorIndices);
/**
* Find the set of variables to be relinearized according to relinearizeThreshold.
* Any variables in the VectorValues delta whose vector magnitude is greater than
* or equal to relinearizeThreshold are returned.
* @param delta The linear delta to check against the threshold
* @param keyFormatter Formatter for printing nonlinear keys during debugging
* @return The set of variable indices in delta whose magnitude is greater than or
* equal to relinearizeThreshold
*/
static KeySet CheckRelinearizationFull(const VectorValues& delta,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold);
/**
* Find the set of variables to be relinearized according to relinearizeThreshold.
* This check is performed recursively, starting at the top of the tree. Once a
* variable in the tree does not need to be relinearized, no further checks in
* that branch are performed. This is an approximation of the Full version, designed
* to save time at the expense of accuracy.
* @param delta The linear delta to check against the threshold
* @param keyFormatter Formatter for printing nonlinear keys during debugging
* @return The set of variable indices in delta whose magnitude is greater than or
* equal to relinearizeThreshold
*/
static KeySet CheckRelinearizationPartial(const ISAM2::Roots& roots,
const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold);
/**
* Update the Newton's method step point, using wildfire
*/
static size_t UpdateGaussNewtonDelta(const ISAM2::Roots& roots,
const KeySet& replacedKeys, double wildfireThreshold, VectorValues* delta);
const KeySet& replacedKeys,
double wildfireThreshold,
VectorValues* delta);
/**
* Update the RgProd (R*g) incrementally taking into account which variables
* have been recalculated in \c replacedKeys. Only used in Dogleg.
*/
static size_t UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys,
const VectorValues& gradAtZero, VectorValues* RgProd);
static size_t UpdateRgProd(const ISAM2::Roots& roots,
const KeySet& replacedKeys,
const VectorValues& gradAtZero,
VectorValues* RgProd);
/**
* Compute the gradient-search point. Only used in Dogleg.
*/
static VectorValues ComputeGradientSearch(const VectorValues& gradAtZero,
const VectorValues& RgProd);
};
}
/* ************************************************************************* */
/**
* Implementation functions for update method
* All of the methods below have clear inputs and outputs, even if not
* functional: iSAM2 is inherintly imperative.
*/
struct GTSAM_EXPORT UpdateImpl {
const ISAM2Params& params_;
const ISAM2UpdateParams& updateParams_;
UpdateImpl(const ISAM2Params& params, const ISAM2UpdateParams& updateParams)
: params_(params), updateParams_(updateParams) {}
// Provide some debugging information at the start of update
static void LogStartingUpdate(const NonlinearFactorGraph& newFactors,
const ISAM2& isam2) {
gttic(pushBackFactors);
const bool debug = ISDEBUG("ISAM2 update");
const bool verbose = ISDEBUG("ISAM2 update verbose");
if (verbose) {
std::cout << "ISAM2::update\n";
isam2.print("ISAM2: ");
}
if (debug || verbose) {
newFactors.print("The new factors are: ");
}
}
// Check relinearization if we're at the nth step, or we are using a looser
// loop relinerization threshold.
bool relinarizationNeeded(size_t update_count) const {
return updateParams_.force_relinearize ||
(params_.enableRelinearization &&
update_count % params_.relinearizeSkip == 0);
}
// Add any new factors \Factors:=\Factors\cup\Factors'.
void pushBackFactors(const NonlinearFactorGraph& newFactors,
NonlinearFactorGraph* nonlinearFactors,
GaussianFactorGraph* linearFactors,
VariableIndex* variableIndex,
FactorIndices* newFactorsIndices,
KeySet* keysWithRemovedFactors) const {
gttic(pushBackFactors);
// Perform the first part of the bookkeeping updates for adding new factors.
// Adds them to the complete list of nonlinear factors, and populates the
// list of new factor indices, both optionally finding and reusing empty
// factor slots.
*newFactorsIndices = nonlinearFactors->add_factors(
newFactors, params_.findUnusedFactorSlots);
// Remove the removed factors
NonlinearFactorGraph removedFactors;
removedFactors.reserve(updateParams_.removeFactorIndices.size());
for (const auto index : updateParams_.removeFactorIndices) {
removedFactors.push_back(nonlinearFactors->at(index));
nonlinearFactors->remove(index);
if (params_.cacheLinearizedFactors) linearFactors->remove(index);
}
// Remove removed factors from the variable index so we do not attempt to
// relinearize them
variableIndex->remove(updateParams_.removeFactorIndices.begin(),
updateParams_.removeFactorIndices.end(),
removedFactors);
*keysWithRemovedFactors = removedFactors.keys();
}
// Get keys from removed factors and new factors, and compute unused keys,
// i.e., keys that are empty now and do not appear in the new factors.
void computeUnusedKeys(const NonlinearFactorGraph& newFactors,
const VariableIndex& variableIndex,
const KeySet& keysWithRemovedFactors,
KeySet* unusedKeys) const {
gttic(computeUnusedKeys);
KeySet removedAndEmpty;
for (Key key : keysWithRemovedFactors) {
if (variableIndex.empty(key))
removedAndEmpty.insert(removedAndEmpty.end(), key);
}
KeySet newFactorSymbKeys = newFactors.keys();
std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(),
newFactorSymbKeys.begin(), newFactorSymbKeys.end(),
std::inserter(*unusedKeys, unusedKeys->end()));
}
// Calculate nonlinear error
void error(const NonlinearFactorGraph& nonlinearFactors,
const Values& estimate, boost::optional<double>* result) const {
gttic(error);
result->reset(nonlinearFactors.error(estimate));
}
// Mark linear update
void gatherInvolvedKeys(const NonlinearFactorGraph& newFactors,
const NonlinearFactorGraph& nonlinearFactors,
const KeySet& keysWithRemovedFactors,
KeySet* markedKeys) const {
gttic(gatherInvolvedKeys);
*markedKeys = newFactors.keys(); // Get keys from new factors
// Also mark keys involved in removed factors
markedKeys->insert(keysWithRemovedFactors.begin(),
keysWithRemovedFactors.end());
// Also mark any provided extra re-eliminate keys
if (updateParams_.extraReelimKeys) {
for (Key key : *updateParams_.extraReelimKeys) {
markedKeys->insert(key);
}
}
// Also, keys that were not observed in existing factors, but whose affected
// keys have been extended now (e.g. smart factors)
if (updateParams_.newAffectedKeys) {
for (const auto& factorAddedKeys : *updateParams_.newAffectedKeys) {
const auto factorIdx = factorAddedKeys.first;
const auto& affectedKeys = nonlinearFactors.at(factorIdx)->keys();
markedKeys->insert(affectedKeys.begin(), affectedKeys.end());
}
}
}
// Update detail, unused, and observed keys from markedKeys
void updateKeys(const KeySet& markedKeys, ISAM2Result* result) const {
gttic(updateKeys);
// Observed keys for detailed results
if (result->detail && params_.enableDetailedResults) {
for (Key key : markedKeys) {
result->detail->variableStatus[key].isObserved = true;
}
}
for (Key index : markedKeys) {
// Only add if not unused
if (result->unusedKeys.find(index) == result->unusedKeys.end())
// Make a copy of these, as we'll soon add to them
result->observedKeys.push_back(index);
}
}
static void CheckRelinearizationRecursiveMap(
const FastMap<char, Vector>& thresholds, const VectorValues& delta,
const ISAM2::sharedClique& clique, KeySet* relinKeys) {
// Check the current clique for relinearization
bool relinearize = false;
for (Key var : *clique->conditional()) {
// Find the threshold for this variable type
const Vector& threshold = thresholds.find(Symbol(var).chr())->second;
const Vector& deltaVar = delta[var];
// Verify the threshold vector matches the actual variable size
if (threshold.rows() != deltaVar.rows())
throw std::invalid_argument(
"Relinearization threshold vector dimensionality for '" +
std::string(1, Symbol(var).chr()) +
"' passed into iSAM2 parameters does not match actual variable "
"dimensionality.");
// Check for relinearization
if ((deltaVar.array().abs() > threshold.array()).any()) {
relinKeys->insert(var);
relinearize = true;
}
}
// If this node was relinearized, also check its children
if (relinearize) {
for (const ISAM2::sharedClique& child : clique->children) {
CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys);
}
}
}
static void CheckRelinearizationRecursiveDouble(
double threshold, const VectorValues& delta,
const ISAM2::sharedClique& clique, KeySet* relinKeys) {
// Check the current clique for relinearization
bool relinearize = false;
for (Key var : *clique->conditional()) {
double maxDelta = delta[var].lpNorm<Eigen::Infinity>();
if (maxDelta >= threshold) {
relinKeys->insert(var);
relinearize = true;
}
}
// If this node was relinearized, also check its children
if (relinearize) {
for (const ISAM2::sharedClique& child : clique->children) {
CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys);
}
}
}
/**
* Find the set of variables to be relinearized according to
* relinearizeThreshold. This check is performed recursively, starting at
* the top of the tree. Once a variable in the tree does not need to be
* relinearized, no further checks in that branch are performed. This is an
* approximation of the Full version, designed to save time at the expense
* of accuracy.
* @param delta The linear delta to check against the threshold
* @param keyFormatter Formatter for printing nonlinear keys during
* debugging
* @return The set of variable indices in delta whose magnitude is greater
* than or equal to relinearizeThreshold
*/
static KeySet CheckRelinearizationPartial(
const ISAM2::Roots& roots, const VectorValues& delta,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
KeySet relinKeys;
for (const ISAM2::sharedClique& root : roots) {
if (relinearizeThreshold.type() == typeid(double))
CheckRelinearizationRecursiveDouble(
boost::get<double>(relinearizeThreshold), delta, root, &relinKeys);
else if (relinearizeThreshold.type() == typeid(FastMap<char, Vector>))
CheckRelinearizationRecursiveMap(
boost::get<FastMap<char, Vector> >(relinearizeThreshold), delta,
root, &relinKeys);
}
return relinKeys;
}
/**
* Find the set of variables to be relinearized according to
* relinearizeThreshold. Any variables in the VectorValues delta whose
* vector magnitude is greater than or equal to relinearizeThreshold are
* returned.
* @param delta The linear delta to check against the threshold
* @param keyFormatter Formatter for printing nonlinear keys during
* debugging
* @return The set of variable indices in delta whose magnitude is greater
* than or equal to relinearizeThreshold
*/
static KeySet CheckRelinearizationFull(
const VectorValues& delta,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
KeySet relinKeys;
if (const double* threshold = boost::get<double>(&relinearizeThreshold)) {
for (const VectorValues::KeyValuePair& key_delta : delta) {
double maxDelta = key_delta.second.lpNorm<Eigen::Infinity>();
if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
}
} else if (const FastMap<char, Vector>* thresholds =
boost::get<FastMap<char, Vector> >(&relinearizeThreshold)) {
for (const VectorValues::KeyValuePair& key_delta : delta) {
const Vector& threshold =
thresholds->find(Symbol(key_delta.first).chr())->second;
if (threshold.rows() != key_delta.second.rows())
throw std::invalid_argument(
"Relinearization threshold vector dimensionality for '" +
std::string(1, Symbol(key_delta.first).chr()) +
"' passed into iSAM2 parameters does not match actual variable "
"dimensionality.");
if ((key_delta.second.array().abs() > threshold.array()).any())
relinKeys.insert(key_delta.first);
}
}
return relinKeys;
}
// Mark keys in \Delta above threshold \beta:
KeySet gatherRelinearizeKeys(const ISAM2::Roots& roots,
const VectorValues& delta,
const KeySet& fixedVariables,
KeySet* markedKeys) const {
gttic(gatherRelinearizeKeys);
// J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}.
KeySet relinKeys =
params_.enablePartialRelinearizationCheck
? CheckRelinearizationPartial(roots, delta,
params_.relinearizeThreshold)
: CheckRelinearizationFull(delta, params_.relinearizeThreshold);
if (updateParams_.forceFullSolve)
relinKeys = CheckRelinearizationFull(delta, 0.0); // for debugging
// Remove from relinKeys any keys whose linearization points are fixed
for (Key key : fixedVariables) {
relinKeys.erase(key);
}
if (updateParams_.noRelinKeys) {
for (Key key : *updateParams_.noRelinKeys) {
relinKeys.erase(key);
}
}
// Add the variables being relinearized to the marked keys
markedKeys->insert(relinKeys.begin(), relinKeys.end());
return relinKeys;
}
// Record relinerization threshold keys in detailed results
void recordRelinearizeDetail(const KeySet& relinKeys,
ISAM2Result::DetailedResults* detail) const {
if (detail && params_.enableDetailedResults) {
for (Key key : relinKeys) {
detail->variableStatus[key].isAboveRelinThreshold = true;
detail->variableStatus[key].isRelinearized = true;
}
}
}
// Mark all cliques that involve marked variables \Theta_{J} and all
// their ancestors.
void findFluid(const ISAM2::Roots& roots, const KeySet& relinKeys,
KeySet* markedKeys,
ISAM2Result::DetailedResults* detail) const {
gttic(findFluid);
for (const auto& root : roots)
// add other cliques that have the marked ones in the separator
root->findAll(relinKeys, markedKeys);
// Relinearization-involved keys for detailed results
if (detail && params_.enableDetailedResults) {
KeySet involvedRelinKeys;
for (const auto& root : roots)
root->findAll(relinKeys, &involvedRelinKeys);
for (Key key : involvedRelinKeys) {
if (!detail->variableStatus[key].isAboveRelinThreshold) {
detail->variableStatus[key].isRelinearizeInvolved = true;
detail->variableStatus[key].isRelinearized = true;
}
}
}
}
/**
* Apply expmap to the given values, but only for indices appearing in
* \c mask. Values are expmapped in-place.
* \param mask Mask on linear indices, only \c true entries are expmapped
*/
static void ExpmapMasked(const VectorValues& delta, const KeySet& mask,
Values* theta) {
gttic(ExpmapMasked);
assert(theta->size() == delta.size());
Values::iterator key_value;
VectorValues::const_iterator key_delta;
#ifdef GTSAM_USE_TBB
for (key_value = theta->begin(); key_value != theta->end(); ++key_value) {
key_delta = delta.find(key_value->key);
#else
for (key_value = theta->begin(), key_delta = delta.begin();
key_value != theta->end(); ++key_value, ++key_delta) {
assert(key_value->key == key_delta->first);
#endif
Key var = key_value->key;
assert(static_cast<size_t>(delta[var].size()) == key_value->value.dim());
assert(delta[var].allFinite());
if (mask.exists(var)) {
Value* retracted = key_value->value.retract_(delta[var]);
key_value->value = *retracted;
retracted->deallocate_();
}
}
}
// Linearize new factors
void linearizeNewFactors(const NonlinearFactorGraph& newFactors,
const Values& theta, size_t numNonlinearFactors,
const FactorIndices& newFactorsIndices,
GaussianFactorGraph* linearFactors) const {
gttic(linearizeNewFactors);
auto linearized = newFactors.linearize(theta);
if (params_.findUnusedFactorSlots) {
linearFactors->resize(numNonlinearFactors);
for (size_t i = 0; i < newFactors.size(); ++i)
(*linearFactors)[newFactorsIndices[i]] = (*linearized)[i];
} else {
linearFactors->push_back(*linearized);
}
assert(linearFactors->size() == numNonlinearFactors);
}
void augmentVariableIndex(const NonlinearFactorGraph& newFactors,
const FactorIndices& newFactorsIndices,
VariableIndex* variableIndex) const {
gttic(augmentVariableIndex);
// Augment the variable index with the new factors
if (params_.findUnusedFactorSlots)
variableIndex->augment(newFactors, newFactorsIndices);
else
variableIndex->augment(newFactors);
// Augment it with existing factors which now affect to more variables:
if (updateParams_.newAffectedKeys) {
for (const auto& factorAddedKeys : *updateParams_.newAffectedKeys) {
const auto factorIdx = factorAddedKeys.first;
variableIndex->augmentExistingFactor(factorIdx, factorAddedKeys.second);
}
}
}
static void LogRecalculateKeys(const ISAM2Result& result) {
const bool debug = ISDEBUG("ISAM2 recalculate");
if (debug) {
std::cout << "markedKeys: ";
for (const Key key : result.markedKeys) {
std::cout << key << " ";
}
std::cout << std::endl;
std::cout << "observedKeys: ";
for (const Key key : result.observedKeys) {
std::cout << key << " ";
}
std::cout << std::endl;
}
}
static FactorIndexSet GetAffectedFactors(const KeyList& keys,
const VariableIndex& variableIndex) {
gttic(GetAffectedFactors);
FactorIndexSet indices;
for (const Key key : keys) {
const FactorIndices& factors(variableIndex[key]);
indices.insert(factors.begin(), factors.end());
}
return indices;
}
// find intermediate (linearized) factors from cache that are passed into
// the affected area
static GaussianFactorGraph GetCachedBoundaryFactors(
const ISAM2::Cliques& orphans) {
GaussianFactorGraph cachedBoundary;
for (const auto& orphan : orphans) {
// retrieve the cached factor and add to boundary
cachedBoundary.push_back(orphan->cachedFactor());
}
return cachedBoundary;
}
};
} // namespace gtsam

File diff suppressed because it is too large Load Diff

View File

@ -20,12 +20,12 @@
#pragma once
#include <gtsam/linear/GaussianBayesTree.h>
#include <gtsam/nonlinear/ISAM2Clique.h>
#include <gtsam/nonlinear/ISAM2Params.h>
#include <gtsam/nonlinear/ISAM2Result.h>
#include <gtsam/nonlinear/ISAM2Clique.h>
#include <gtsam/nonlinear/ISAM2UpdateParams.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/linear/GaussianBayesTree.h>
#include <vector>
@ -73,8 +73,8 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
* This is \c mutable because it is used internally to not update delta_
* until it is needed.
*/
mutable KeySet
deltaReplacedMask_; // TODO(dellaert): Make sure accessed in the right way
mutable KeySet deltaReplacedMask_; // TODO(dellaert): Make sure accessed in
// the right way
/** All original nonlinear factors are stored here to use during
* relinearization */
@ -97,11 +97,11 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
///< periodic relinearization
public:
typedef ISAM2 This; ///< This class
typedef BayesTree<ISAM2Clique> Base; ///< The BayesTree base class
typedef Base::Clique Clique; ///< A clique
typedef Base::sharedClique sharedClique; ///< Shared pointer to a clique
typedef Base::Cliques Cliques; ///< List of Clique typedef from base class
using This = ISAM2; ///< This class
using Base = BayesTree<ISAM2Clique>; ///< The BayesTree base class
using Clique = Base::Clique; ///< A clique
using sharedClique = Base::sharedClique; ///< Shared pointer to a clique
using Cliques = Base::Cliques; ///< List of Cliques
/** Create an empty ISAM2 instance */
explicit ISAM2(const ISAM2Params& params);
@ -175,9 +175,9 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
* @return An ISAM2Result struct containing information about the update
* @note No default parameters to avoid ambiguous call errors.
*/
virtual ISAM2Result update(
const NonlinearFactorGraph& newFactors, const Values& newTheta,
const ISAM2UpdateParams& updateParams);
virtual ISAM2Result update(const NonlinearFactorGraph& newFactors,
const Values& newTheta,
const ISAM2UpdateParams& updateParams);
/** Marginalize out variables listed in leafKeys. These keys must be leaves
* in the BayesTree. Throws MarginalizeNonleafException if non-leaves are
@ -226,7 +226,6 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
return traits<VALUE>::Retract(theta_.at<VALUE>(key), delta);
}
/** Compute an estimate for a single variable using its incomplete linear
* delta computed during the last update. This is faster than calling the
* no-argument version of calculateEstimate, which operates on all variables.
@ -243,9 +242,6 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
/// @name Public members for non-typical usage
/// @{
/** Internal implementation functions */
struct Impl;
/** Compute an estimate using a complete delta computed by a full
* back-substitution.
*/
@ -268,13 +264,6 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
/** Access the nonlinear variable index */
const KeySet& getFixedVariables() const { return fixedVariables_; }
size_t lastAffectedVariableCount;
size_t lastAffectedFactorCount;
size_t lastAffectedCliqueCount;
size_t lastAffectedMarkedCount;
mutable size_t lastBacksubVariableCount;
size_t lastNnzTop;
const ISAM2Params& params() const { return params_; }
/** prints out clique statistics */
@ -292,40 +281,39 @@ class GTSAM_EXPORT ISAM2 : public BayesTree<ISAM2Clique> {
/// @}
protected:
/// Remove marked top and either recalculate in batch or incrementally.
void recalculate(const ISAM2UpdateParams& updateParams,
const KeySet& relinKeys, ISAM2Result* result);
// Do a batch step - reorder and relinearize all variables
void recalculateBatch(const ISAM2UpdateParams& updateParams,
KeySet* affectedKeysSet, ISAM2Result* result);
// retrieve all factors that ONLY contain the affected variables
// (note that the remaining stuff is summarized in the cached factors)
GaussianFactorGraph relinearizeAffectedFactors(
const ISAM2UpdateParams& updateParams, const FastList<Key>& affectedKeys,
const KeySet& relinKeys);
void recalculateIncremental(const ISAM2UpdateParams& updateParams,
const KeySet& relinKeys,
const FastList<Key>& affectedKeys,
KeySet* affectedKeysSet, Cliques* orphans,
ISAM2Result* result);
/**
* Add new variables to the ISAM2 system.
* @param newTheta Initial values for new variables
* @param theta Current solution to be augmented with new initialization
* @param delta Current linear delta to be augmented with zeros
* @param deltaNewton
* @param RgProd
* @param keyFormatter Formatter for printing nonlinear keys during debugging
* @param variableStatus optional detailed result structure
*/
void addVariables(const Values& newTheta);
void addVariables(const Values& newTheta,
ISAM2Result::DetailedResults* detail = 0);
/**
* Remove variables from the ISAM2 system.
*/
void removeVariables(const KeySet& unusedKeys);
/**
* Apply expmap to the given values, but only for indices appearing in
* \c mask. Values are expmapped in-place.
* \param mask Mask on linear indices, only \c true entries are expmapped
*/
void expmapMasked(const KeySet& mask);
FactorIndexSet getAffectedFactors(const FastList<Key>& keys) const;
GaussianFactorGraph::shared_ptr relinearizeAffectedFactors(
const FastList<Key>& affectedKeys, const KeySet& relinKeys) const;
GaussianFactorGraph getCachedBoundaryFactors(const Cliques& orphans);
virtual boost::shared_ptr<KeySet> recalculate(
const KeySet& markedKeys, const KeySet& relinKeys,
const KeyVector& observedKeys, const KeySet& unusedIndices,
const boost::optional<FastMap<Key, int> >& constrainKeys,
ISAM2Result* result);
void updateDelta(bool forceFullSolve = false) const;
}; // ISAM2
@ -334,5 +322,3 @@ template <>
struct traits<ISAM2> : public Testable<ISAM2> {};
} // namespace gtsam
#include <gtsam/nonlinear/ISAM2-impl.h>

View File

@ -19,7 +19,9 @@
#include <gtsam/linear/VectorValues.h>
#include <gtsam/linear/linearAlgorithms-inst.h>
#include <gtsam/nonlinear/ISAM2Clique.h>
#include <stack>
#include <utility>
using namespace std;
@ -304,7 +306,7 @@ void ISAM2Clique::findAll(const KeySet& markedMask, KeySet* keys) const {
static const bool debug = false;
// does the separator contain any of the variables?
bool found = false;
for (Key key : conditional()->parents()) {
for (Key key : conditional_->parents()) {
if (markedMask.exists(key)) {
found = true;
break;
@ -312,14 +314,34 @@ void ISAM2Clique::findAll(const KeySet& markedMask, KeySet* keys) const {
}
if (found) {
// then add this clique
keys->insert(conditional()->beginFrontals(), conditional()->endFrontals());
keys->insert(conditional_->beginFrontals(), conditional_->endFrontals());
if (debug) print("Key(s) marked in clique ");
if (debug) cout << "so marking key " << conditional()->front() << endl;
if (debug) cout << "so marking key " << conditional_->front() << endl;
}
for (const auto& child : children) {
child->findAll(markedMask, keys);
}
}
/* ************************************************************************* */
void ISAM2Clique::addGradientAtZero(VectorValues* g) const {
// Loop through variables in each clique, adding contributions
DenseIndex position = 0;
for (auto it = conditional_->begin(); it != conditional_->end(); ++it) {
const DenseIndex dim = conditional_->getDim(it);
const Vector contribution = gradientContribution_.segment(position, dim);
VectorValues::iterator values_it;
bool success;
std::tie(values_it, success) = g->tryInsert(*it, contribution);
if (!success) values_it->second += contribution;
position += dim;
}
// Recursively add contributions from children
for (const auto& child : children) {
child->addGradientAtZero(g);
}
}
/* ************************************************************************* */
} // namespace gtsam

View File

@ -75,9 +75,12 @@ class GTSAM_EXPORT ISAM2Clique
/** Access the cached factor */
Base::FactorType::shared_ptr& cachedFactor() { return cachedFactor_; }
/** Access the gradient contribution */
/// Access the gradient contribution
const Vector& gradientContribution() const { return gradientContribution_; }
/// Recursively add gradient at zero to g
void addGradientAtZero(VectorValues* g) const;
bool equals(const This& other, double tol = 1e-9) const;
/** print this node */

View File

@ -234,8 +234,8 @@ struct GTSAM_EXPORT ISAM2Params {
Factorization _factorization = ISAM2Params::CHOLESKY,
bool _cacheLinearizedFactors = true,
const KeyFormatter& _keyFormatter =
DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter
)
DefaultKeyFormatter, ///< see ISAM2::Params::keyFormatter,
bool _enableDetailedResults = false)
: optimizationParams(_optimizationParams),
relinearizeThreshold(_relinearizeThreshold),
relinearizeSkip(_relinearizeSkip),
@ -244,7 +244,7 @@ struct GTSAM_EXPORT ISAM2Params {
factorization(_factorization),
cacheLinearizedFactors(_cacheLinearizedFactors),
keyFormatter(_keyFormatter),
enableDetailedResults(false),
enableDetailedResults(_enableDetailedResults),
enablePartialRelinearizationCheck(false),
findUnusedFactorSlots(false) {}

View File

@ -24,8 +24,8 @@
#include <gtsam/linear/GaussianBayesTree.h>
#include <gtsam/nonlinear/DoglegOptimizerImpl.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/ISAM2Params.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <boost/variant.hpp>
@ -96,7 +96,22 @@ struct GTSAM_EXPORT ISAM2Result {
*/
FactorIndices newFactorsIndices;
/** A struct holding detailed results, which must be enabled with
/** Unused keys, and indices for unused keys,
* i.e., keys that are empty now and do not appear in the new factors.
*/
KeySet unusedKeys;
/** keys for variables that were observed, i.e., not unused. */
KeyVector observedKeys;
/** Keys of variables that had factors removed. */
KeySet keysWithRemovedFactors;
/** All keys that were marked during the update process. */
KeySet markedKeys;
/**
* A struct holding detailed results, which must be enabled with
* ISAM2Params::enableDetailedResults.
*/
struct DetailedResults {
@ -132,15 +147,24 @@ struct GTSAM_EXPORT ISAM2Result {
inRootClique(false) {}
};
/** The status of each variable during this update, see VariableStatus.
*/
FastMap<Key, VariableStatus> variableStatus;
using StatusMap = FastMap<Key, VariableStatus>;
/// The status of each variable during this update, see VariableStatus.
StatusMap variableStatus;
};
/** Detailed results, if enabled by ISAM2Params::enableDetailedResults. See
* Detail for information about the results data stored here. */
boost::optional<DetailedResults> detail;
explicit ISAM2Result(bool enableDetailedResults = false) {
if (enableDetailedResults) detail.reset(DetailedResults());
}
/// Return pointer to detail, 0 if no detail requested
DetailedResults* details() { return detail.get_ptr(); }
/// Print results
void print(const std::string str = "") const {
using std::cout;
cout << str << " Reelimintated: " << variablesReeliminated

View File

@ -16,11 +16,11 @@
#pragma once
#include <boost/optional.hpp>
#include <gtsam/base/FastList.h>
#include <gtsam/dllexport.h> // GTSAM_EXPORT
#include <gtsam/inference/Key.h> // Key, KeySet
#include <gtsam/nonlinear/ISAM2Result.h> //FactorIndices
#include <gtsam/dllexport.h> // GTSAM_EXPORT
#include <gtsam/inference/Key.h> // Key, KeySet
#include <gtsam/nonlinear/ISAM2Result.h> //FactorIndices
#include <boost/optional.hpp>
namespace gtsam {
@ -63,8 +63,12 @@ struct GTSAM_EXPORT ISAM2UpdateParams {
* depend on Keys `X(2)`, `X(3)`. Next call to ISAM2::update() must include
* its `newAffectedKeys` field with the map `13 -> {X(2), X(3)}`.
*/
boost::optional<FastMap<FactorIndex,KeySet>> newAffectedKeys{boost::none};
boost::optional<FastMap<FactorIndex, KeySet>> newAffectedKeys{boost::none};
/** By default, iSAM2 uses a wildfire update scheme that stops updating when
* the deltas become too small down in the tree. This flagg forces a full
* solve instead. */
bool forceFullSolve{false};
};
} // namespace gtsam
} // namespace gtsam

View File

@ -18,6 +18,8 @@
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/base/Testable.h>
#include <string>
namespace gtsam {
/**
@ -70,10 +72,14 @@ namespace gtsam {
/** implement functions needed for Testable */
/** print */
virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const {
std::cout << s << "PriorFactor on " << keyFormatter(this->key()) << "\n";
traits<T>::Print(prior_, " prior mean: ");
this->noiseModel_->print(" noise model: ");
if (this->noiseModel_)
this->noiseModel_->print(" noise model: ");
else
std::cout << "no noise model" << std::endl;
}
/** equals */

View File

@ -43,7 +43,7 @@ namespace gtsam {
// keep track of which domains changed
changed[v] = false;
// loop over all factors/constraints for variable v
const VariableIndex::Factors& factors = index[v];
const FactorIndices& factors = index[v];
for(size_t f: factors) {
// if not already a singleton
if (!domains[v].isSingleton()) {

View File

@ -4,7 +4,7 @@
* @author Michael Kaess
*/
#include <CppUnitLite/TestHarness.h>
#include <gtsam/nonlinear/ISAM2.h>
#include <tests/smallExample.h>
#include <gtsam/slam/PriorFactor.h>
@ -14,7 +14,6 @@
#include <gtsam/geometry/Pose2.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/ISAM2.h>
#include <gtsam/nonlinear/Marginals.h>
#include <gtsam/linear/GaussianBayesNet.h>
#include <gtsam/linear/GaussianBayesTree.h>
@ -23,10 +22,12 @@
#include <gtsam/base/debug.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/treeTraversal-inst.h>
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/list_of.hpp>
#include <gtsam/base/deprecated/LieScalar.h>
using namespace boost::assign;
#include <boost/range/adaptor/map.hpp>
using namespace boost::assign;
namespace br { using namespace boost::adaptors; using namespace boost::range; }
using namespace std;
@ -34,7 +35,6 @@ using namespace gtsam;
using boost::shared_ptr;
static const SharedNoiseModel model;
static const LieScalar Zero(0);
// SETDEBUG("ISAM2 update", true);
// SETDEBUG("ISAM2 update verbose", true);
@ -47,9 +47,11 @@ SharedDiagonal brNoise = noiseModel::Diagonal::Sigmas((Vector(2) << M_PI/100.0,
ISAM2 createSlamlikeISAM2(
boost::optional<Values&> init_values = boost::none,
boost::optional<NonlinearFactorGraph&> full_graph = boost::none,
const ISAM2Params& params = ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0, 0, false, true),
const ISAM2Params& params = ISAM2Params(ISAM2GaussNewtonParams(0.001), 0.0,
0, false, true,
ISAM2Params::CHOLESKY, true,
DefaultKeyFormatter, true),
size_t maxPoses = 10) {
// These variables will be reused and accumulate factors and values
ISAM2 isam(params);
Values fullinit;
@ -282,34 +284,6 @@ bool isam_check(const NonlinearFactorGraph& fullgraph, const Values& fullinit, c
return nodeGradientsOk && expectedGradOk && totalGradOk && isamEqual && isamTreeEqual && consistent;
}
/* ************************************************************************* */
TEST(ISAM2, AddFactorsStep1)
{
NonlinearFactorGraph nonlinearFactors;
nonlinearFactors += PriorFactor<LieScalar>(10, Zero, model);
nonlinearFactors += NonlinearFactor::shared_ptr();
nonlinearFactors += PriorFactor<LieScalar>(11, Zero, model);
NonlinearFactorGraph newFactors;
newFactors += PriorFactor<LieScalar>(1, Zero, model);
newFactors += PriorFactor<LieScalar>(2, Zero, model);
NonlinearFactorGraph expectedNonlinearFactors;
expectedNonlinearFactors += PriorFactor<LieScalar>(10, Zero, model);
expectedNonlinearFactors += PriorFactor<LieScalar>(1, Zero, model);
expectedNonlinearFactors += PriorFactor<LieScalar>(11, Zero, model);
expectedNonlinearFactors += PriorFactor<LieScalar>(2, Zero, model);
const FactorIndices expectedNewFactorIndices = list_of(1)(3);
FactorIndices actualNewFactorIndices;
ISAM2::Impl::AddFactorsStep1(newFactors, true, &nonlinearFactors, &actualNewFactorIndices);
EXPECT(assert_equal(expectedNonlinearFactors, nonlinearFactors));
EXPECT(assert_container_equality(expectedNewFactorIndices, actualNewFactorIndices));
}
/* ************************************************************************* */
TEST(ISAM2, simple)
{
@ -692,25 +666,24 @@ namespace {
}
/* ************************************************************************* */
TEST(ISAM2, marginalizeLeaves1)
{
TEST(ISAM2, marginalizeLeaves1) {
ISAM2 isam;
NonlinearFactorGraph factors;
factors += PriorFactor<LieScalar>(0, Zero, model);
factors += PriorFactor<double>(0, 0.0, model);
factors += BetweenFactor<LieScalar>(0, 1, Zero, model);
factors += BetweenFactor<LieScalar>(1, 2, Zero, model);
factors += BetweenFactor<LieScalar>(0, 2, Zero, model);
factors += BetweenFactor<double>(0, 1, 0.0, model);
factors += BetweenFactor<double>(1, 2, 0.0, model);
factors += BetweenFactor<double>(0, 2, 0.0, model);
Values values;
values.insert(0, Zero);
values.insert(1, Zero);
values.insert(2, Zero);
values.insert(0, 0.0);
values.insert(1, 0.0);
values.insert(2, 0.0);
FastMap<Key,int> constrainedKeys;
constrainedKeys.insert(make_pair(0,0));
constrainedKeys.insert(make_pair(1,1));
constrainedKeys.insert(make_pair(2,2));
FastMap<Key, int> constrainedKeys;
constrainedKeys.insert(make_pair(0, 0));
constrainedKeys.insert(make_pair(1, 1));
constrainedKeys.insert(make_pair(2, 2));
isam.update(factors, values, FactorIndices(), constrainedKeys);
@ -719,29 +692,28 @@ TEST(ISAM2, marginalizeLeaves1)
}
/* ************************************************************************* */
TEST(ISAM2, marginalizeLeaves2)
{
TEST(ISAM2, marginalizeLeaves2) {
ISAM2 isam;
NonlinearFactorGraph factors;
factors += PriorFactor<LieScalar>(0, Zero, model);
factors += PriorFactor<double>(0, 0.0, model);
factors += BetweenFactor<LieScalar>(0, 1, Zero, model);
factors += BetweenFactor<LieScalar>(1, 2, Zero, model);
factors += BetweenFactor<LieScalar>(0, 2, Zero, model);
factors += BetweenFactor<LieScalar>(2, 3, Zero, model);
factors += BetweenFactor<double>(0, 1, 0.0, model);
factors += BetweenFactor<double>(1, 2, 0.0, model);
factors += BetweenFactor<double>(0, 2, 0.0, model);
factors += BetweenFactor<double>(2, 3, 0.0, model);
Values values;
values.insert(0, Zero);
values.insert(1, Zero);
values.insert(2, Zero);
values.insert(3, Zero);
values.insert(0, 0.0);
values.insert(1, 0.0);
values.insert(2, 0.0);
values.insert(3, 0.0);
FastMap<Key,int> constrainedKeys;
constrainedKeys.insert(make_pair(0,0));
constrainedKeys.insert(make_pair(1,1));
constrainedKeys.insert(make_pair(2,2));
constrainedKeys.insert(make_pair(3,3));
FastMap<Key, int> constrainedKeys;
constrainedKeys.insert(make_pair(0, 0));
constrainedKeys.insert(make_pair(1, 1));
constrainedKeys.insert(make_pair(2, 2));
constrainedKeys.insert(make_pair(3, 3));
isam.update(factors, values, FactorIndices(), constrainedKeys);
@ -750,38 +722,37 @@ TEST(ISAM2, marginalizeLeaves2)
}
/* ************************************************************************* */
TEST(ISAM2, marginalizeLeaves3)
{
TEST(ISAM2, marginalizeLeaves3) {
ISAM2 isam;
NonlinearFactorGraph factors;
factors += PriorFactor<LieScalar>(0, Zero, model);
factors += PriorFactor<double>(0, 0.0, model);
factors += BetweenFactor<LieScalar>(0, 1, Zero, model);
factors += BetweenFactor<LieScalar>(1, 2, Zero, model);
factors += BetweenFactor<LieScalar>(0, 2, Zero, model);
factors += BetweenFactor<double>(0, 1, 0.0, model);
factors += BetweenFactor<double>(1, 2, 0.0, model);
factors += BetweenFactor<double>(0, 2, 0.0, model);
factors += BetweenFactor<LieScalar>(2, 3, Zero, model);
factors += BetweenFactor<double>(2, 3, 0.0, model);
factors += BetweenFactor<LieScalar>(3, 4, Zero, model);
factors += BetweenFactor<LieScalar>(4, 5, Zero, model);
factors += BetweenFactor<LieScalar>(3, 5, Zero, model);
factors += BetweenFactor<double>(3, 4, 0.0, model);
factors += BetweenFactor<double>(4, 5, 0.0, model);
factors += BetweenFactor<double>(3, 5, 0.0, model);
Values values;
values.insert(0, Zero);
values.insert(1, Zero);
values.insert(2, Zero);
values.insert(3, Zero);
values.insert(4, Zero);
values.insert(5, Zero);
values.insert(0, 0.0);
values.insert(1, 0.0);
values.insert(2, 0.0);
values.insert(3, 0.0);
values.insert(4, 0.0);
values.insert(5, 0.0);
FastMap<Key,int> constrainedKeys;
constrainedKeys.insert(make_pair(0,0));
constrainedKeys.insert(make_pair(1,1));
constrainedKeys.insert(make_pair(2,2));
constrainedKeys.insert(make_pair(3,3));
constrainedKeys.insert(make_pair(4,4));
constrainedKeys.insert(make_pair(5,5));
FastMap<Key, int> constrainedKeys;
constrainedKeys.insert(make_pair(0, 0));
constrainedKeys.insert(make_pair(1, 1));
constrainedKeys.insert(make_pair(2, 2));
constrainedKeys.insert(make_pair(3, 3));
constrainedKeys.insert(make_pair(4, 4));
constrainedKeys.insert(make_pair(5, 5));
isam.update(factors, values, FactorIndices(), constrainedKeys);
@ -790,24 +761,23 @@ TEST(ISAM2, marginalizeLeaves3)
}
/* ************************************************************************* */
TEST(ISAM2, marginalizeLeaves4)
{
TEST(ISAM2, marginalizeLeaves4) {
ISAM2 isam;
NonlinearFactorGraph factors;
factors += PriorFactor<LieScalar>(0, Zero, model);
factors += BetweenFactor<LieScalar>(0, 2, Zero, model);
factors += BetweenFactor<LieScalar>(1, 2, Zero, model);
factors += PriorFactor<double>(0, 0.0, model);
factors += BetweenFactor<double>(0, 2, 0.0, model);
factors += BetweenFactor<double>(1, 2, 0.0, model);
Values values;
values.insert(0, Zero);
values.insert(1, Zero);
values.insert(2, Zero);
values.insert(0, 0.0);
values.insert(1, 0.0);
values.insert(2, 0.0);
FastMap<Key,int> constrainedKeys;
constrainedKeys.insert(make_pair(0,0));
constrainedKeys.insert(make_pair(1,1));
constrainedKeys.insert(make_pair(2,2));
FastMap<Key, int> constrainedKeys;
constrainedKeys.insert(make_pair(0, 0));
constrainedKeys.insert(make_pair(1, 1));
constrainedKeys.insert(make_pair(2, 2));
isam.update(factors, values, FactorIndices(), constrainedKeys);