31 #include <boost/range/adaptors.hpp> 32 #include <boost/range/algorithm/copy.hpp> 61 :
public JunctionTree<ISAM2BayesTree, GaussianFactorGraph> {
68 : Base(eliminationTree) {}
79 enum { COLAMD } algorithm;
87 static size_t UpdateGaussNewtonDelta(
const ISAM2::Roots& roots,
88 const KeySet& replacedKeys,
89 double wildfireThreshold,
97 const KeySet& replacedKeys,
118 : params_(params), updateParams_(updateParams) {}
122 const ISAM2& isam2) {
123 gttic(pushBackFactors);
128 std::cout <<
"ISAM2::update\n";
129 isam2.
print(
"ISAM2: ");
132 if (debug || verbose) {
133 newFactors.
print(
"The new factors are: ");
151 KeySet* keysWithRemovedFactors)
const {
152 gttic(pushBackFactors);
158 *newFactorsIndices = nonlinearFactors->
add_factors(
165 removedFactors.
push_back(nonlinearFactors->
at(index));
166 nonlinearFactors->
remove(index);
175 *keysWithRemovedFactors = removedFactors.
keys();
182 const KeySet& keysWithRemovedFactors,
183 KeySet* unusedKeys)
const {
184 gttic(computeUnusedKeys);
186 for (
Key key : keysWithRemovedFactors) {
188 removedAndEmpty.insert(removedAndEmpty.end(),
key);
191 std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(),
192 newFactorSymbKeys.begin(), newFactorSymbKeys.end(),
193 std::inserter(*unusedKeys, unusedKeys->end()));
198 const Values& estimate, boost::optional<double>*
result)
const {
200 result->reset(nonlinearFactors.
error(estimate));
206 const KeySet& keysWithRemovedFactors,
207 KeySet* markedKeys)
const {
208 gttic(gatherInvolvedKeys);
209 *markedKeys = newFactors.
keys();
211 markedKeys->insert(keysWithRemovedFactors.begin(),
212 keysWithRemovedFactors.end());
217 markedKeys->insert(key);
225 const auto factorIdx = factorAddedKeys.first;
226 const auto& affectedKeys = nonlinearFactors.
at(factorIdx)->keys();
227 markedKeys->insert(affectedKeys.begin(), affectedKeys.end());
237 for (
Key key : markedKeys) {
238 result->
detail->variableStatus[
key].isObserved =
true;
242 for (
Key index : markedKeys) {
254 bool relinearize =
false;
255 for (
Key var : *clique->conditional()) {
257 const Vector& threshold = thresholds.find(
Symbol(var).chr())->second;
259 const Vector& deltaVar = delta[var];
262 if (threshold.rows() != deltaVar.rows())
263 throw std::invalid_argument(
264 "Relinearization threshold vector dimensionality for '" +
265 std::string(1,
Symbol(var).chr()) +
266 "' passed into iSAM2 parameters does not match actual variable " 270 if ((deltaVar.array().abs() > threshold.array()).any()) {
271 relinKeys->insert(var);
279 CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys);
288 bool relinearize =
false;
289 for (
Key var : *clique->conditional()) {
291 if (maxDelta >= threshold) {
292 relinKeys->insert(var);
300 CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys);
323 if (relinearizeThreshold.type() ==
typeid(double))
324 CheckRelinearizationRecursiveDouble(
325 boost::get<double>(relinearizeThreshold), delta,
root, &relinKeys);
327 CheckRelinearizationRecursiveMap(
350 if (
const double* threshold = boost::get<double>(&relinearizeThreshold)) {
353 if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
359 thresholds->find(
Symbol(key_delta.first).
chr())->second;
360 if (threshold.rows() != key_delta.second.rows())
361 throw std::invalid_argument(
362 "Relinearization threshold vector dimensionality for '" +
363 std::string(1,
Symbol(key_delta.first).
chr()) +
364 "' passed into iSAM2 parameters does not match actual variable " 366 if ((key_delta.second.array().abs() > threshold.array()).any())
367 relinKeys.insert(key_delta.first);
377 const KeySet& fixedVariables,
378 KeySet* markedKeys)
const {
379 gttic(gatherRelinearizeKeys);
383 ? CheckRelinearizationPartial(roots, delta,
387 relinKeys = CheckRelinearizationFull(delta, 0.0);
390 for (
Key key : fixedVariables) {
391 relinKeys.erase(
key);
395 relinKeys.erase(key);
400 markedKeys->insert(relinKeys.begin(), relinKeys.end());
408 for (
Key key : relinKeys) {
421 for (
const auto&
root : roots)
423 root->findAll(relinKeys, markedKeys);
428 for (
const auto&
root : roots)
429 root->findAll(relinKeys, &involvedRelinKeys);
430 for (
Key key : involvedRelinKeys) {
447 assert(theta->
size() == delta.
size());
448 Values::iterator key_value;
451 for (key_value = theta->
begin(); key_value != theta->
end(); ++key_value) {
452 key_delta = delta.
find(key_value->key);
454 for (key_value = theta->
begin(), key_delta = delta.
begin();
455 key_value != theta->
end(); ++key_value, ++key_delta) {
456 assert(key_value->key == key_delta->first);
458 Key var = key_value->key;
459 assert(static_cast<size_t>(delta[var].
size()) == key_value->value.dim());
460 assert(delta[var].allFinite());
463 key_value->value = *retracted;
471 const Values& theta,
size_t numNonlinearFactors,
474 gttic(linearizeNewFactors);
475 auto linearized = newFactors.
linearize(theta);
477 linearFactors->
resize(numNonlinearFactors);
478 for (
size_t i = 0;
i < newFactors.
size(); ++
i)
479 (*linearFactors)[newFactorsIndices[
i]] = (*linearized)[
i];
483 assert(linearFactors->
size() == numNonlinearFactors);
489 gttic(augmentVariableIndex);
492 variableIndex->
augment(newFactors, newFactorsIndices);
494 variableIndex->
augment(newFactors);
499 const auto factorIdx = factorAddedKeys.first;
509 std::cout <<
"markedKeys: ";
511 std::cout << key <<
" ";
513 std::cout << std::endl;
514 std::cout <<
"observedKeys: ";
516 std::cout << key <<
" ";
518 std::cout << std::endl;
524 gttic(GetAffectedFactors);
526 for (
const Key key : keys) {
528 indices.insert(factors.begin(), factors.end());
539 for (
const auto& orphan : orphans) {
541 cachedBoundary.
push_back(orphan->cachedFactor());
544 return cachedBoundary;
bool findUnusedFactorSlots
static void LogRecalculateKeys(const ISAM2Result &result)
bool empty(Key variable) const
Return true if no factors associated with a variable.
boost::optional< FastList< Key > > extraReelimKeys
void augment(const FG &factors, boost::optional< const FactorIndices & > newFactorIndices=boost::none)
unsigned char chr() const
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
FastVector< FactorIndex > FactorIndices
Define collection types:
FactorIndices add_factors(const CONTAINER &factors, bool useEmptySlots=false)
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
const ISAM2UpdateParams & updateParams_
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
virtual void deallocate_() const =0
static void CheckRelinearizationRecursiveMap(const FastMap< char, Vector > &thresholds, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
virtual Value * retract_(const Vector &delta) const =0
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
bool exists(const VALUE &e) const
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, boost::optional< double > *result) const
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
void augmentExistingFactor(const FactorIndex factorIndex, const KeySet &newKeys)
const ISAM2Params & params_
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
static void CheckRelinearizationRecursiveDouble(double threshold, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
ISAM2JunctionTree(const GaussianEliminationTree &eliminationTree)
UpdateImpl(const ISAM2Params ¶ms, const ISAM2UpdateParams &updateParams)
Class that stores detailed iSAM2 result.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
const_iterator end() const
static KeySet CheckRelinearizationPartial(const ISAM2::Roots &roots, const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
boost::shared_ptr< This > shared_ptr
StatusMap variableStatus
The status of each variable during this update, see VariableStatus.
value_type KeyValuePair
Typedef to pair<Key, Vector>
Base::sharedClique sharedClique
Shared pointer to a clique.
Values::const_iterator const_iterator
Const iterator over vector values.
static SmartStereoProjectionParams params
const_iterator begin() const
bool relinarizationNeeded(size_t update_count) const
RelinearizationThreshold relinearizeThreshold
boost::shared_ptr< This > shared_ptr
const sharedFactor at(size_t i) const
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool enableRelinearization
static KeySet CheckRelinearizationFull(const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
boost::optional< FastMap< Key, int > > constrainedKeys
FactorIndices removeFactorIndices
bool enablePartialRelinearizationCheck
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
The junction tree, template bodies.
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
FastVector< sharedClique > Roots
void reserve(size_t size)
boost::variant< double, FastMap< char, Vector > > RelinearizationThreshold
static void ExpmapMasked(const VectorValues &delta, const KeySet &mask, Values *theta)
double error(const Values &values) const
Container::iterator get(Container &c, Position position)
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
boost::optional< FastList< Key > > noRelinKeys
bool enableDetailedResults
iterator begin()
Iterator over variables.
boost::optional< FastMap< FactorIndex, KeySet > > newAffectedKeys
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
std::uint64_t Key
Integer nonlinear key type.
ISAM2::sharedClique bayesTree
JunctionTree< ISAM2BayesTree, GaussianFactorGraph > Base
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
boost::optional< DetailedResults > detail
bool cacheLinearizedFactors
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const