ConcurrentFilteringAndSmoothing.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 // \callgraph
21 #pragma once
22 
23 #include <gtsam_unstable/dllexport.h>
25 #include <gtsam/nonlinear/Values.h>
27 
28 namespace gtsam {
29 
30 // Forward declare the Filter and Smoother classes for the 'synchronize' function
31 class ConcurrentFilter;
32 class ConcurrentSmoother;
33 
34 void GTSAM_UNSTABLE_EXPORT synchronize(ConcurrentFilter& filter, ConcurrentSmoother& smoother);
35 
39 class GTSAM_UNSTABLE_EXPORT ConcurrentFilter {
40 public:
41  typedef boost::shared_ptr<ConcurrentFilter> shared_ptr;
42 
45 
47  virtual ~ConcurrentFilter() {};
48 
50  virtual void print(
51  const std::string& s = "Concurrent Filter:\n",
52  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const = 0;
53 
55  virtual bool equals(const ConcurrentFilter& rhs, double tol = 1e-9) const = 0;
56 
61  virtual void presync() {};
62 
70  virtual void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues) = 0;
71 
80  virtual void getSmootherFactors(NonlinearFactorGraph& smootherFactors, Values& smootherValues) = 0;
81 
88  virtual void synchronize(const NonlinearFactorGraph& summarizedFactors, const Values& separatorValues) = 0;
89 
94  virtual void postsync() {};
95 
96 }; // ConcurrentFilter
97 
101 class GTSAM_UNSTABLE_EXPORT ConcurrentSmoother {
102 public:
103  typedef boost::shared_ptr<ConcurrentSmoother> shared_ptr;
104 
107 
109  virtual ~ConcurrentSmoother() {};
110 
112  virtual void print(
113  const std::string& s = "Concurrent Smoother:\n",
114  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const = 0;
115 
117  virtual bool equals(const ConcurrentSmoother& rhs, double tol = 1e-9) const = 0;
118 
123  virtual void presync() {};
124 
132  virtual void getSummarizedFactors(NonlinearFactorGraph& summarizedFactors, Values& separatorValues) = 0;
133 
143  virtual void synchronize(const NonlinearFactorGraph& smootherFactors, const Values& smootherValues,
144  const NonlinearFactorGraph& summarizedFactors, const Values& rootValues) = 0;
145 
150  virtual void postsync() {};
151 
152 }; // ConcurrentSmoother
153 
154 namespace internal {
155 
159  const KeySet& remainingKeys, const GaussianFactorGraph::Eliminate& eliminateFunction);
160 
161 }
162 
163 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Rot2 theta
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
boost::shared_ptr< ConcurrentFilter > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< ConcurrentSmoother > shared_ptr
Linear Factor Graph where all factors are Gaussians.
traits
Definition: chartTesting.h:28
void synchronize(ConcurrentFilter &filter, ConcurrentSmoother &smoother)
boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
const G double tol
Definition: Group.h:83


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:49