46 const boost::optional<
FastList<Key> >& keysToMove,
const boost::optional< FactorIndices >& removeFactorIndices) {
51 const bool debug =
false;
53 if(debug) std::cout <<
"ConcurrentIncrementalFilter::update Begin" << std::endl;
61 if(removeFactorIndices){
62 removedFactors.insert(removedFactors.end(), removeFactorIndices->begin(), removeFactorIndices->end());
66 boost::optional<FastMap<Key,int> > orderingConstraints = boost::none;
67 if(keysToMove && keysToMove->size() > 0) {
73 orderingConstraints->operator[](key_value.key) = group;
78 for(
const auto key_value: newTheta) {
79 orderingConstraints->operator[](key_value.key) = group;
83 orderingConstraints->operator[](
key) = 0;
89 boost::optional<FastList<Key> > noRelinKeys = boost::none;
92 boost::optional<FastList<Key> > additionalKeys = boost::none;
93 if(keysToMove && keysToMove->size() > 0) {
94 std::set<Key> markedKeys;
95 for(
Key key: *keysToMove) {
99 while(*key_iter !=
key) {
100 markedKeys.insert(*key_iter);
108 additionalKeys =
FastList<Key>(markedKeys.begin(), markedKeys.end());
113 ISAM2Result isam2Result =
isam2_.
update(newFactors, newTheta, removedFactors, orderingConstraints, noRelinKeys, additionalKeys);
116 if(keysToMove && keysToMove->size() > 0) {
118 gttic(cache_smoother_factors);
123 for(
size_t slot: removedFactorSlots) {
131 for(
Key key: *keysToMove) {
134 gttoc(cache_smoother_factors);
141 for(
size_t index: deletedFactorsIndices) {
159 if(debug) std::cout <<
"ConcurrentIncrementalFilter::update End" << std::endl;
179 const bool debug =
false;
181 if(debug) std::cout <<
"ConcurrentIncrementalFilter::synchronize Begin" << std::endl;
195 values.
insert(smootherSummarizationValues);
196 for(
Key key: newSeparatorKeys) {
205 noRelinKeys.push_back(key_value.key);
221 if(debug) std::cout <<
"ConcurrentIncrementalFilter::synchronize End" << std::endl;
229 gttic(get_summarized_factors);
239 gttoc(get_summarized_factors);
245 gttic(get_smoother_factors);
251 gttoc(get_smoother_factors);
271 if(std::find(clique->conditional()->beginParents(), clique->conditional()->endParents(),
key) != clique->conditional()->endParents()) {
274 for(
Key idx: clique->conditional()->frontals()) {
275 additionalKeys.insert(idx);
294 const auto& slots = variableIndex[
key];
295 removedFactorSlots.insert(removedFactorSlots.end(), slots.begin(), slots.end());
299 std::sort(removedFactorSlots.begin(), removedFactorSlots.end());
300 removedFactorSlots.erase(std::unique(removedFactorSlots.begin(), removedFactorSlots.end()), removedFactorSlots.end());
303 for(
size_t index: factorsToIgnore) {
304 removedFactorSlots.erase(std::remove(removedFactorSlots.begin(), removedFactorSlots.end(), index), removedFactorSlots.end());
307 return removedFactorSlots;
319 shortcutKeys.insert(factor->begin(), factor->end());
323 shortcutKeys.insert(
key);
349 std::set<ISAM2Clique::shared_ptr> separatorCliques;
350 for(
Key key: separatorKeys) {
352 separatorCliques.insert( clique );
358 for(
Key key: clique->conditional()->frontals()) {
359 cliqueKeys.push_back(
key);
362 std::sort(cliqueKeys.begin(), cliqueKeys.end());
365 std::set<size_t> cliqueFactorSlots;
366 for(
Key key: cliqueKeys) {
370 std::set<Key> factorKeys(factor->begin(), factor->end());
371 if(std::includes(cliqueKeys.begin(), cliqueKeys.end(), factorKeys.begin(), factorKeys.end())) {
372 cliqueFactorSlots.insert(slot);
380 cliqueFactorSlots.erase(slot);
385 for(
size_t slot: cliqueFactorSlots) {
390 std::set<ISAM2Clique::shared_ptr> childCliques;
393 childCliques.insert(clique->children.begin(), clique->children.end());
397 childCliques.erase(clique);
410 return filterSummarization;
GaussianFactorGraph::Eliminate getEliminationFunction() const
size_t nonlinearVariables
The number of variables that can be relinearized.
size_t variablesRelinearized
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
boost::shared_ptr< This > shared_ptr
size_t variablesReeliminated
FactorIndices newFactorsIndices
void insert(Key j, const Value &val)
FastVector< FactorIndex > FactorIndices
Define collection types:
void print(const std::string &s="Concurrent Incremental Filter:\n", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
ISAM2 isam2_
The iSAM2 inference engine.
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const boost::optional< FastList< Key > > &keysToMove=boost::none, const boost::optional< FactorIndices > &removeFactorIndices=boost::none)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool equals(const ConcurrentFilter &rhs, double tol=1e-9) const override
NonlinearFactorGraph graph
void getSmootherFactors(NonlinearFactorGraph &smootherFactors, Values &smootherValues) override
bool equals(const Values &other, double tol=1e-9) const
NonlinearFactorGraph calculateFilterSummarization() const
NonlinearFactorGraph previousSmootherSummarization_
The smoother summarization on the old separator sent by the smoother during the last synchronization...
static void RecursiveMarkAffectedKeys(const Key &key, const ISAM2Clique::shared_ptr &clique, std::set< Key > &additionalKeys)
void getSummarizedFactors(NonlinearFactorGraph &filterSummarization, Values &filterSummarizationValues) override
FactorIndices newFactorsIndices
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
const ValueType at(Key j) const
virtual bool equals(const ISAM2 &other, double tol=1e-9) const
void marginalizeLeaves(const FastList< Key > &leafKeys, boost::optional< FactorIndices & > marginalFactorsIndices=boost::none, boost::optional< FactorIndices & > deletedFactorsIndices=boost::none)
void updateShortcut(const NonlinearFactorGraph &removedFactors)
size_t variablesRelinearized
boost::shared_ptr< This > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
boost::shared_ptr< This > shared_ptr
NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
const ISAM2Params & params() const
size_t iterations
The number of optimizer iterations performed.
void synchronize(const NonlinearFactorGraph &smootherSummarization, const Values &smootherSummarizationValues) override
const sharedFactor at(size_t i) const
std::vector< float > Values
FactorIndices currentSmootherSummarizationSlots_
The slots in factor graph that correspond to the current smoother summarization on the current separa...
const KeySet & getFixedVariables() const
size_t linearVariables
The number of variables that must keep a constant linearization point.
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
size_t variablesReeliminated
KeyVector::const_iterator const_iterator
Const iterator over keys.
NonlinearFactorGraph smootherShortcut_
A set of conditional factors from the old separator to the current separator (recursively calculated ...
const NonlinearFactorGraph & getFactorsUnsafe() const
Values smootherValues_
A temporary holding place for the linearization points of all keys being sent to the smoother...
bool equal(const T &obj1, const T &obj2, double tol)
const VariableIndex & getVariableIndex() const
std::uint64_t Key
Integer nonlinear key type.
NonlinearFactorGraph smootherFactors_
A temporary holding place for the set of full nonlinear factors being sent to the smoother...
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
static FactorIndices FindAdjacentFactors(const ISAM2 &isam2, const FastList< Key > &keys, const FactorIndices &factorsToIgnore)
const Values & getLinearizationPoint() const
Access the current linearization point.